Designed a velocity controller for the series elastic intake.

It's stable!  This gives us a place to start for controlling it.
We'll have to try it in real life at some point to see if it's right.

Change-Id: I09381b7cba42084f9d5052f54197616fd9dd8c2c
diff --git a/frc971/control_loops/python/control_loop.py b/frc971/control_loops/python/control_loop.py
index c2fe755..82d138a 100644
--- a/frc971/control_loops/python/control_loop.py
+++ b/frc971/control_loops/python/control_loop.py
@@ -291,8 +291,13 @@
 
   def CorrectObserver(self, U):
     """Runs the correct step of the observer update."""
-    self.X_hat += numpy.linalg.inv(self.A) * self.L * (
-        self.Y - self.C * self.X_hat - self.D * U)
+    # See if the KalmanGain exists.  That lets us avoid inverting A.
+    # Otherwise, do the inversion.
+    if hasattr(self, 'KalmanGain'):
+      KalmanGain = self.KalmanGain
+    else:
+      KalmanGain = numpy.linalg.inv(self.A) * self.L
+    self.X_hat += KalmanGain * (self.Y - self.C * self.X_hat - self.D * U)
 
   def UpdateObserver(self, U):
     """Updates the observer given the provided U."""
@@ -511,3 +516,22 @@
     self.Kv = (self.free_speed / (12.0 - self.resistance * self.free_current))
     # Torque constant
     self.Kt = self.stall_torque / self.stall_current
+
+
+class BAG(object):
+  # BAG motor specs available at http://motors.vex.com/vexpro-motors/bag-motor
+  def __init__(self):
+    # Stall Torque in (N m)
+    self.stall_torque = 0.43
+    # Stall Current in (Amps)
+    self.stall_current = 53.0
+    # Free Speed in (rad/s)
+    self.free_speed = 13180.0 / 60.0 * 2.0 * numpy.pi
+    # Free Current in (Amps)
+    self.free_current = 1.8
+    # Resistance of the motor (Ohms)
+    self.resistance = 12.0 / self.stall_current
+    # Motor velocity constant (radians / (sec * volt))
+    self.Kv = (self.free_speed / (12.0 - self.resistance * self.free_current))
+    # Torque constant (N * m / A)
+    self.Kt = self.stall_torque / self.stall_current
diff --git a/y2018/control_loops/python/BUILD b/y2018/control_loops/python/BUILD
index 04a244e..042c39e 100644
--- a/y2018/control_loops/python/BUILD
+++ b/y2018/control_loops/python/BUILD
@@ -56,3 +56,16 @@
   ],
   restricted_to = ['//tools:k8'],
 )
+
+py_binary(
+  name = 'intake',
+  srcs = [
+    'intake.py',
+  ],
+  deps = [
+    '//external:python-gflags',
+    '//external:python-glog',
+    '//frc971/control_loops/python:controls',
+  ],
+  restricted_to = ['//tools:k8'],
+)
diff --git a/y2018/control_loops/python/intake.py b/y2018/control_loops/python/intake.py
index d75d438..200eb64 100755
--- a/y2018/control_loops/python/intake.py
+++ b/y2018/control_loops/python/intake.py
@@ -1,245 +1,364 @@
-#!/usr/bin/python3
+#!/usr/bin/python
 
-# This code was used to select the gear ratio for the intake.
-# Run it from the command line and it displays the time required
-# to rotate the intake 180 degrees.
-# 
-# Michael Schuh
-# January 20, 2018
-
-import math
+from frc971.control_loops.python import control_loop
+from frc971.control_loops.python import controls
 import numpy
-import scipy.integrate
+import sys
+import matplotlib
+from matplotlib import pylab
+import gflags
+import glog
 
-# apt-get install python-scipy python3-scipy python-numpy python3-numpy
+FLAGS = gflags.FLAGS
 
-pi = math.pi
-pi2 = 2.0*pi
-rad_to_deg = 180.0/pi
-inches_to_meters = 0.0254
-lbs_to_kg = 1.0/2.2
-newton_to_lbf = 0.224809
-newton_meters_to_ft_lbs = 0.73756
-run_count = 0
-theta_travel = 0.0
+try:
+  gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+except gflags.DuplicateFlagError:
+  pass
 
-def to_deg(angle):
-  return (angle*rad_to_deg)
+class Intake(control_loop.ControlLoop):
+  def __init__(self, name="Intake"):
+    super(Intake, self).__init__(name)
+    self.motor = control_loop.BAG()
+    # TODO(constants): Update all of these & retune poles.
+    # Stall Torque in N m
+    self.stall_torque = self.motor.stall_torque
+    # Stall Current in Amps
+    self.stall_current = self.motor.stall_current
+    # Free Speed in RPM
+    self.free_speed = self.motor.free_speed
+    # Free Current in Amps
+    self.free_current = self.motor.free_current
 
-def to_rad(angle):
-  return (angle/rad_to_deg)
+    # Resistance of the motor
+    self.resistance = self.motor.resistance
+    # Motor velocity constant
+    self.Kv = self.motor.Kv
+    # Torque constant
+    self.Kt = self.motor.Kt
+    # Gear ratio
+    self.G = 1.0 / 100.0
 
-def to_rotations(angle):
-  return (angle/pi2)
+    self.motor_inertia = 0.000006
 
-def time_derivative(x, t, voltage, c1, c2, c3):
-  global run_count
-  theta, omega = x
-  dxdt = [omega, -c1*omega + c3*math.sin(theta) + c2*voltage]
-  run_count = run_count + 1
+    # Series elastic moment of inertia
+    self.Je = self.motor_inertia / (self.G * self.G)
+    # Grabber moment of inertia
+    self.Jo = 0.295
 
-  #print ('dxdt = ',dxdt,' repr(dxdt) = ', repr(dxdt))
-  return dxdt
+    # Spring constant (N m / radian)
+    self.Ks = 30.0
 
-def get_distal_angle(theta_proximal):
-  # For the proximal angle = -50 degrees, the distal angle is -180 degrees
-  # For the proximal angle =  10 degrees, the distal angle is  -90 degrees
-  distal_angle = to_rad(-180.0 - (-50.0-to_deg(theta_proximal))*(180.0-90.0)/(50.0+10.0))
-  return distal_angle
-  
+    # Control loop time step
+    self.dt = 0.00505
 
-def get_180_degree_time(c1,c2,c3,voltage,gear_ratio,motor_free_speed):
-  #print ("# step     time    theta    angular_speed   angular_acceleration  theta   angular_speed  motor_speed motor_speed_fraction")
-  #print ("#          (sec)   (rad)      (rad/sec)        (rad/sec^2)      (rotations) (rotations/sec)    (rpm)   (fraction)")
-  global run_count
-  global theta_travel
+    # State is [output_position, output_velocity,
+    #           elastic_position, elastic_velocity]
+    # The output position is the absolute position of the intake arm.
+    # The elastic position is the absolute position of the motor side of the
+    # series elastic.
+    # Input is [voltage]
 
-  if ( True ):
-    # Gravity is assisting the motion.
-    theta_start = 0.0
-    theta_target = pi
-  elif ( False ):
-    # Gravity is assisting the motion.
-    theta_start = 0.0
-    theta_target = -pi
-  elif ( False ):
-    # Gravity is slowing the motion.
-    theta_start = pi
-    theta_target = 0.0
-  elif ( False ):
-    # Gravity is slowing the motion.
-    theta_start = -pi
-    theta_target = 0.0
-  elif ( False ):
-    # This is for the proximal arm motion.
-    theta_start = to_rad(-50.0)
-    theta_target = to_rad(10.0)
+    self.A_continuous = numpy.matrix(
+        [[0.0, 1.0, 0.0, 0.0],
+         [(-self.Ks / self.Jo), 0.0, (self.Ks / self.Jo), 0.0],
+         [0.0, 0.0, 0.0, 1.0],
+         [(self.Ks / self.Je), 0.0, (-self.Ks / self.Je), \
+          -self.Kt / (self.Je * self.resistance * self.Kv * self.G * self.G)]])
 
-  theta_half = 0.5*(theta_start + theta_target)
-  if (theta_start > theta_target):
-    voltage = -voltage
-  theta = theta_start
-  theta_travel = theta_start - theta_target 
-  if ( run_count == 0 ):
-    print ("# Theta Start = %.2f radians End = %.2f Theta travel %.2f Theta half = %.2f Voltage = %.2f" % (theta_start,theta_target,theta_travel,theta_half, voltage))
-    print ("# Theta Start = %.2f degrees End = %.2f Theta travel %.2f Theta half = %.2f Voltage = %.2f" % (to_deg(theta_start),to_deg(theta_target),to_deg(theta_travel),to_deg(theta_half), voltage))
-  omega = 0.0
-  time = 0.0
-  delta_time = 0.01 # time step in seconds
-  for step in range(1, 5000):
-     t = numpy.array([time, time + delta_time])
-     time = time + delta_time
-     x = [theta, omega]
-     angular_acceleration = -c1*omega + c2*voltage
-     x_n_plus_1 = scipy.integrate.odeint(time_derivative,x,t,args=(voltage,c1,c2,c3))
-     #print ('x_n_plus_1 = ',x_n_plus_1)
-     #print ('repr(x_n_plus_1) = ',repr(x_n_plus_1))
-     theta, omega = x_n_plus_1[1]
-     #theta= x_n_plus_1[0]
-     #omega = x_n_plus_1[1]
-     if ( False ):
-       print ("%4d  %8.4f %8.2f          %8.4f          %8.4f    %8.3f    %8.3f     %8.3f      %8.3f" % \
-         (step, time, theta, omega, angular_acceleration, to_rotations(theta), \
-         to_rotations(omega), omega*gear_ratio*60.0/pi2, omega*gear_ratio/motor_free_speed ))
-     if (theta_start < theta_target):
-       # Angle is increasing through the motion.
-       if (theta > theta_half):
-         break
-     else:
-       # Angle is decreasing through the motion.
-       if (theta < theta_half):
-         break
-       
-  #print ("# step     time    theta    angular_speed   angular_acceleration  theta   angular_speed  motor_speed motor_speed_fraction")
-  #print ("#          (sec)   (rad)      (rad/sec)        (rad/sec^2)      (rotations) (rotations/sec)    (rpm)   (fraction)")
-  #print ("# Total time for 1/2 rotation of arm is %0.2f" % (time*2))
-  return (2.0*time)
+    # Start with the unmodified input
+    self.B_continuous = numpy.matrix(
+        [[0.0],
+         [0.0],
+         [0.0],
+         [self.Kt / (self.G * self.Je * self.resistance)]])
 
-def main():
-  gravity = 9.8 # m/sec^2 Gravity Constant
-  gravity = 0.0 # m/sec^2 Gravity Constant - Use 0.0 for the intake.  It is horizontal.
-  voltage_nominal = 12 # Volts
-  
-  # Vex 775 Pro motor specs from http://banebots.com/p/M2-RS550-120
-  motor_name = "Vex 775 Pro motor specs from http://banebots.com/p/M2-RS550-120"
-  current_stall = 134 # amps stall current
-  current_no_load = 0.7 # amps no load current
-  torque_stall = 710/1000.0 # N-m Stall Torque
-  speed_no_load_rpm = 18730 # RPM no load speed
-  
-  if ( True ):
-    # Bag motor from https://www.vexrobotics.com/217-3351.html
-    motor_name = "Bag motor from https://www.vexrobotics.com/217-3351.html"
-    current_stall = 53.0 # amps stall current
-    current_no_load = 1.8 # amps no load current
-    torque_stall = 0.4 # N-m Stall Torque
-    speed_no_load_rpm = 13180.0 # RPM no load speed
-  
-  if ( False ):
-    # Mini CIM motor from https://www.vexrobotics.com/217-3371.html
-    motor_name = "Mini CIM motor from https://www.vexrobotics.com/217-3371.html"
-    current_stall = 89.0 # amps stall current
-    current_no_load = 3.0 # amps no load current
-    torque_stall = 1.4 # N-m Stall Torque
-    speed_no_load_rpm = 5840.0 # RPM no load speed
+    self.C = numpy.matrix([[1.0, 0.0, -1.0, 0.0],
+                           [0.0, 0.0, 1.0, 0.0]])
+    self.D = numpy.matrix([[0.0],
+                           [0.0]])
 
-  # How many motors are we using?
-  num_motors = 1
+    self.A, self.B = self.ContinuousToDiscrete(
+        self.A_continuous, self.B_continuous, self.dt)
 
-  # Motor values
-  print ("# Motor: %s" % (motor_name))
-  print ("# Number of motors: %d" % (num_motors))
-  print ("# Stall torque: %.1f n-m" % (torque_stall))
-  print ("# Stall current: %.1f amps" % (current_stall))
-  print ("# No load current: %.1f amps" % (current_no_load))
-  print ("# No load speed: %.0f rpm" % (speed_no_load_rpm))
-  
-  # Constants from motor values
-  resistance_motor = voltage_nominal/current_stall 
-  speed_no_load_rps = speed_no_load_rpm/60.0 # Revolutions per second no load speed
-  speed_no_load = speed_no_load_rps*2.0*pi
-  Kt = num_motors*torque_stall/current_stall # N-m/A torque constant
-  Kv_rpm = speed_no_load_rpm /(voltage_nominal - resistance_motor*current_no_load)  # rpm/V
-  Kv = Kv_rpm*2.0*pi/60.0 # rpm/V
-  
-  # Robot Geometry and physics
-  length_proximal_arm = inches_to_meters*47.34 # m Length of arm connected to the robot base
-  length_distal_arm = inches_to_meters*44.0 # m Length of arm that holds the cube
-  length_intake_arm =  inches_to_meters*9.0 # m Length of intake arm from the pivot point to where the big roller contacts a cube.
-  mass_cube = 6.0*lbs_to_kg  # Weight of the cube in Kgrams
-  mass_proximal_arm = 5.5*lbs_to_kg # Weight of proximal arm
-  mass_distal_arm = 3.5*lbs_to_kg # Weight of distal arm
-  mass_distal = mass_cube + mass_distal_arm
-  mass_proximal = mass_proximal_arm + mass_distal
-  radius_to_proximal_arm_cg = 22.0*inches_to_meters # m Length from arm pivot point to arm CG
-  radius_to_distal_arm_cg = 10.0*inches_to_meters # m Length from arm pivot point to arm CG
+    controllability = controls.ctrb(self.A, self.B)
+    glog.debug('ctrb: ' + repr(numpy.linalg.matrix_rank(controllability)))
 
-  radius_to_distal_cg = ( length_distal_arm*mass_cube + radius_to_distal_arm_cg*mass_distal_arm)/mass_distal
-  radius_to_proximal_cg = ( length_proximal_arm*mass_distal + radius_to_proximal_arm_cg*mass_proximal_arm)/mass_proximal
-  J_cube = length_distal_arm*length_distal_arm*mass_cube 
-  # Kg m^2 Moment of inertia of the proximal arm
-  J_proximal_arm = radius_to_proximal_arm_cg*radius_to_proximal_arm_cg*mass_distal_arm 
-  # Kg m^2 Moment of inertia distal arm and cube at end of proximal arm.
-  J_distal_arm_and_cube_at_end_of_proximal_arm = length_proximal_arm*length_proximal_arm*mass_distal 
-  J_distal_arm = radius_to_distal_arm_cg*radius_to_distal_arm_cg*mass_distal_arm # Kg m^2 Moment of inertia of the distal arm
-  J = J_distal_arm_and_cube_at_end_of_proximal_arm + J_proximal_arm # Moment of inertia of the arm with the cube on the end
-  # Intake claw 
-  J_intake = 0.295 # Kg m^2 Moment of inertia of intake
-  J = J_intake
+    observability = controls.ctrb(self.A.T, self.C.T)
+    glog.debug('obs: ' + repr(numpy.linalg.matrix_rank(observability)))
 
-  gear_ratio = 140.0 # Guess at the gear ratio
-  gear_ratio = 100.0 # Guess at the gear ratio
-  gear_ratio = 90.0 # Guess at the gear ratio
+    glog.debug('A_continuous ' + repr(self.A_continuous))
+    glog.debug('B_continuous ' + repr(self.B_continuous))
 
-  error_margine = 1.0
-  voltage = 10.0 # voltage for the motor.  Assuming a loaded robot so not using 12 V.
-  # It might make sense to use a lower motor frees peed when the voltage is not a full 12 Volts.
-  # motor_free_speed = Kv*voltage
-  motor_free_speed = speed_no_load
-  
-  print ("# Kt = %f N-m/A\n# Kv_rpm = %f rpm/V\n# Kv = %f radians/V" % (Kt, Kv_rpm, Kv))
-  print ("# %.2f Ohms Resistance of the motor " % (resistance_motor))
-  print ("# %.2f kg Cube weight" % (mass_cube))
-  print ("# %.2f kg Proximal Arm mass" % (mass_proximal_arm))
-  print ("# %.2f kg Distal Arm mass" % (mass_distal_arm))
-  print ("# %.2f kg Distal Arm and Cube weight" % (mass_distal))
-  print ("# %.2f m Length from distal arm pivot point to arm CG" % (radius_to_distal_arm_cg))
-  print ("# %.2f m Length from distal arm pivot point to arm and cube cg" % (radius_to_distal_cg))
-  print ("# %.2f kg-m^2 Moment of inertia of the cube about the arm pivot point" % (J_cube))
-  print ("# %.2f m Length from proximal arm pivot point to arm CG" % (radius_to_proximal_arm_cg))
-  print ("# %.2f m Length from proximal arm pivot point to arm and cube cg" % (radius_to_proximal_cg))
-  print ("# %.2f m  Proximal arm length" % (length_proximal_arm))
-  print ("# %.2f m  Distal arm length" % (length_distal_arm))
+    self.K = numpy.matrix(numpy.zeros((1, 4)))
 
-  print ("# %.2f kg-m^2 Moment of inertia of the intake about the intake pivot point" % (J_intake))
-  print ("# %.2f kg-m^2 Moment of inertia of the distal arm about the arm pivot point" % (J_distal_arm))
-  print ("# %.2f kg-m^2 Moment of inertia of the proximal arm about the arm pivot point" % (J_proximal_arm))
-  print ("# %.2f kg-m^2 Moment of inertia of the distal arm and cube mass about the proximal arm pivot point" % (J_distal_arm_and_cube_at_end_of_proximal_arm))
-  print ("# %.2f kg-m^2 Moment of inertia of the intake the intake pivot point (J value used in simulation)" % (J))
-  print ("# %d Number of motors" % (num_motors))
-  
-  print ("# %.2f V Motor voltage" % (voltage))
-  for gear_ratio in range(60, 241, 10):
-    c1 = Kt*gear_ratio*gear_ratio/(Kv*resistance_motor*J)
-    c2 = gear_ratio*Kt/(J*resistance_motor)
-    c3 = radius_to_proximal_cg*mass_proximal*gravity/J
-  
-    if ( False ):
-      print ("# %.8f 1/sec C1 constant" % (c1))
-      print ("# %.2f 1/sec C2 constant" % (c2))
-      print ("# %.2f 1/(V sec^2) C3 constant" % (c3))
-      print ("# %.2f RPM Free speed at motor voltage" % (voltage*Kv_rpm))
-  
-    torque_90_degrees = radius_to_distal_cg*mass_distal*gravity
-    voltage_90_degrees = resistance_motor*torque_90_degrees/(gear_ratio*Kt)
-    torque_peak = gear_ratio*num_motors*torque_stall
-    torque_peak_ft_lbs = torque_peak * newton_meters_to_ft_lbs
-    normal_force = torque_peak/length_intake_arm
-    normal_force_lbf = newton_to_lbf*normal_force 
-    time_required = get_180_degree_time(c1,c2,c3,voltage,gear_ratio,motor_free_speed)
-    print ("Time for %.1f degrees for gear ratio %3.0f is %.2f seconds.  Peak (stall) torque %3.0f nm %3.0f ft-lb Normal force at intake end %3.0f N %2.0f lbf" % \
-      (to_deg(theta_travel),gear_ratio,time_required,
-       torque_peak,torque_peak_ft_lbs,normal_force,normal_force_lbf))
-  
+    q_pos = 0.05
+    q_vel = 2.65
+    self.Q = numpy.matrix(numpy.diag([(q_pos ** 2.0), (q_vel ** 2.0),
+                                      (q_pos ** 2.0), (q_vel ** 2.0)]))
+
+    r_nm = 0.025
+    self.R = numpy.matrix(numpy.diag([(r_nm ** 2.0), (r_nm ** 2.0)]))
+
+    self.KalmanGain, self.Q_steady = controls.kalman(
+        A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
+
+    self.L = self.A * self.KalmanGain
+
+    # The box formed by U_min and U_max must encompass all possible values,
+    # or else Austin's code gets angry.
+    self.U_max = numpy.matrix([[12.0]])
+    self.U_min = numpy.matrix([[-12.0]])
+
+    self.Kff = controls.TwoStateFeedForwards(self.B, self.Q)
+
+    self.InitializeState()
+
+
+class DelayedIntake(Intake):
+  def __init__(self, name="DelayedIntake"):
+    super(DelayedIntake, self).__init__(name=name)
+
+    self.A_undelayed = self.A
+    self.B_undelayed = self.B
+
+    self.C_unaugmented = self.C
+    self.C = numpy.matrix(numpy.zeros((2, 5)))
+    self.C[0:2, 0:4] = self.C_unaugmented
+
+    # Model this as X[4] is the last power.  And then B applies to the last
+    # power.  This lets us model the 1 cycle PWM delay accurately.
+    self.A = numpy.matrix(numpy.zeros((5, 5)))
+    self.A[0:4, 0:4] = self.A_undelayed
+    self.A[0:4, 4] = self.B_undelayed
+    self.B = numpy.matrix(numpy.zeros((5, 1)))
+    self.B[4, 0] = 1.0
+
+    # Coordinate transform fom absolute angles to relative angles.
+    # [output_position, output_velocity, spring_angle, spring_velocity, voltage]
+    abs_to_rel = numpy.matrix([[ 1.0,  0.0, 0.0, 0.0, 0.0],
+                               [ 0.0,  1.0, 0.0, 0.0, 0.0],
+                               [-1.0,  0.0, 1.0, 0.0, 0.0],
+                               [ 0.0, -1.0, 0.0, 1.0, 0.0],
+                               [ 0.0,  0.0, 0.0, 0.0, 1.0]])
+    # and back again.
+    rel_to_abs = numpy.matrix(numpy.linalg.inv(abs_to_rel))
+
+    # Now, get A and B in the relative coordinate system.
+    self.A_transformed_full = abs_to_rel * self.A * rel_to_abs
+    self.B_transformed_full = abs_to_rel * self.B
+
+    # Pull out the components of the dynamics which don't include the spring
+    # output positoin so we can do partial state feedback on what we care about.
+    self.A_transformed = self.A_transformed_full[1:5, 1:5]
+    self.B_transformed = self.B_transformed_full[1:5, 0]
+
+    glog.debug('A_transformed_full ' + str(self.A_transformed_full))
+    glog.debug('B_transformed_full ' + str(self.B_transformed_full))
+    glog.debug('A_transformed ' + str(self.A_transformed))
+    glog.debug('B_transformed ' + str(self.B_transformed))
+
+    # Now, let's design a controller in
+    #   [output_velocity, spring_position, spring_velocity, delayed_voltage]
+    # space.
+
+    q_output_vel = 0.20
+    q_spring_pos = 0.05
+    q_spring_vel = 3.0
+    q_voltage = 100.0
+    self.Q_lqr = numpy.matrix(numpy.diag(
+        [1.0 / (q_output_vel ** 2.0),
+         1.0 / (q_spring_pos ** 2.0),
+         1.0 / (q_spring_vel ** 2.0),
+         1.0 / (q_voltage ** 2.0)]))
+
+    self.R = numpy.matrix([[(1.0 / (12.0 ** 2.0))]])
+
+    self.K_transformed = controls.dlqr(self.A_transformed, self.B_transformed,
+                                       self.Q_lqr, self.R)
+
+    # Write the controller back out in the absolute coordinate system.
+    self.K = numpy.hstack((numpy.matrix([[0.0]]),
+                           self.K_transformed)) * abs_to_rel
+
+    glog.debug('Poles are %s for %s',
+        repr(numpy.linalg.eig(
+            self.A_transformed -
+            self.B_transformed * self.K_transformed)[0]), self._name)
+    glog.debug('K is %s', repr(self.K_transformed))
+
+    # Design a kalman filter here as well.
+    q_pos = 0.05
+    q_vel = 2.65
+    q_volts = 0.005
+    self.Q = numpy.matrix(numpy.diag([(q_pos ** 2.0), (q_vel ** 2.0),
+                                      (q_pos ** 2.0), (q_vel ** 2.0),
+                                      (q_volts ** 2.0)]))
+
+    r_nm = 0.025
+    self.R = numpy.matrix(numpy.diag([(r_nm ** 2.0), (r_nm ** 2.0)]))
+
+    self.KalmanGain, self.Q_steady = controls.kalman(
+        A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
+
+    self.L = self.A * self.KalmanGain
+
+    # The box formed by U_min and U_max must encompass all possible values,
+    # or else Austin's code gets angry.
+    self.U_max = numpy.matrix([[12.0]])
+    self.U_min = numpy.matrix([[-12.0]])
+
+    self.InitializeState()
+
+
+class ScenarioPlotter(object):
+  def __init__(self):
+    # Various lists for graphing things.
+    self.t = []
+    self.x = []
+    self.v = []
+    self.goal_v = []
+    self.a = []
+    self.spring = []
+    self.x_hat = []
+    self.u = []
+
+  def run_test(self, intake, iterations=400, controller_intake=None,
+             observer_intake=None):
+    """Runs the intake plant with an initial condition and goal.
+
+      Test for whether the goal has been reached and whether the separation
+      goes outside of the initial and goal values by more than
+      max_separation_error.
+
+      Prints out something for a failure of either condition and returns
+      False if tests fail.
+      Args:
+        intake: intake object to use.
+        iterations: Number of timesteps to run the model for.
+        controller_intake: Intake object to get K from, or None if we should
+            use intake.
+        observer_intake: Intake object to use for the observer, or None if we
+            should use the actual state.
+    """
+
+    if controller_intake is None:
+      controller_intake = intake
+
+    vbat = 12.0
+
+    if self.t:
+      initial_t = self.t[-1] + intake.dt
+    else:
+      initial_t = 0
+
+    # Delay U by 1 cycle in our simulation to make it more realistic.
+    last_U = numpy.matrix([[0.0]])
+
+    for i in xrange(iterations):
+      X_hat = intake.X
+
+      if observer_intake is not None:
+        X_hat = observer_intake.X_hat
+        self.x_hat.append(observer_intake.X_hat[0, 0])
+
+      goal_angle = 3.0
+      goal_velocity = numpy.clip((goal_angle - X_hat[0, 0]) * 6.0, -10.0, 10.0)
+
+      self.goal_v.append(goal_velocity)
+
+      # Nominal: 1.8 N at 0.25 m -> 0.45 N m
+      # Nominal: 13 N at 0.25 m at 0.5 radians -> 3.25 N m -> 6 N m / radian
+
+      R = numpy.matrix([[0.0],
+                        [goal_velocity],
+                        [0.0],
+                        [goal_velocity],
+                        [goal_velocity / (intake.G * intake.Kv)]])
+      U = controller_intake.K * (R - X_hat) + R[4, 0]
+
+      U[0, 0] = numpy.clip(U[0, 0], -vbat, vbat)
+
+      self.x.append(intake.X[0, 0])
+      self.spring.append((intake.X[2, 0] - intake.X[0, 0]) * intake.Ks)
+
+      if self.v:
+        last_v = self.v[-1]
+      else:
+        last_v = 0
+
+      self.v.append(intake.X[1, 0])
+      self.a.append((self.v[-1] - last_v) / intake.dt)
+
+      if observer_intake is not None:
+        observer_intake.Y = intake.Y
+        observer_intake.CorrectObserver(U)
+
+      intake.Update(last_U + 0.0)
+
+      if observer_intake is not None:
+        observer_intake.PredictObserver(U)
+
+      self.t.append(initial_t + i * intake.dt)
+      self.u.append(U[0, 0])
+      last_U = U
+
+  def Plot(self):
+    pylab.subplot(3, 1, 1)
+    pylab.plot(self.t, self.x, label='x')
+    pylab.plot(self.t, self.x_hat, label='x_hat')
+    pylab.legend()
+
+    spring_ax1 = pylab.subplot(3, 1, 2)
+    spring_ax1.plot(self.t, self.u, 'k', label='u')
+    spring_ax2 = spring_ax1.twinx()
+    spring_ax2.plot(self.t, self.spring, label='spring_angle')
+    spring_ax1.legend(loc=2)
+    spring_ax2.legend()
+
+    accel_ax1 = pylab.subplot(3, 1, 3)
+    accel_ax1.plot(self.t, self.a, 'r', label='a')
+
+    accel_ax2 = accel_ax1.twinx()
+    accel_ax2.plot(self.t, self.v, label='v')
+    accel_ax2.plot(self.t, self.goal_v, label='goal_v')
+    accel_ax1.legend(loc=2)
+    accel_ax2.legend()
+
+    pylab.show()
+
+
+def main(argv):
+  scenario_plotter = ScenarioPlotter()
+
+  intake = Intake()
+  intake_controller = DelayedIntake()
+  observer_intake = DelayedIntake()
+
+  # Test moving the intake with constant separation.
+  scenario_plotter.run_test(intake, controller_intake=intake_controller,
+                            observer_intake=observer_intake, iterations=200)
+
+  if FLAGS.plot:
+    scenario_plotter.Plot()
+
+  # Write the generated constants out to a file.
+  if len(argv) != 5:
+    glog.fatal('Expected .h file name and .cc file name for the intake and integral intake.')
+  else:
+    namespaces = ['y2018', 'control_loops', 'superstructure']
+    intake = Intake('Intake')
+    loop_writer = control_loop.ControlLoopWriter(
+        'Intake', [intake], namespaces=namespaces)
+    loop_writer.Write(argv[1], argv[2])
+
+    integral_intake = IntegralIntake('IntegralIntake')
+    integral_loop_writer = control_loop.ControlLoopWriter(
+        'IntegralIntake', [integral_intake], namespaces=namespaces)
+    integral_loop_writer.Write(argv[3], argv[4])
+
+
 if __name__ == '__main__':
-   main()
+  argv = FLAGS(sys.argv)
+  glog.init()
+  sys.exit(main(argv))
diff --git a/y2018/control_loops/python/intake_simple.py b/y2018/control_loops/python/intake_simple.py
new file mode 100644
index 0000000..9b6ffb1
--- /dev/null
+++ b/y2018/control_loops/python/intake_simple.py
@@ -0,0 +1,273 @@
+#!/usr/bin/python3
+
+# This code was used to select the gear ratio for the intake.
+# Run it from the command line and it displays the time required
+# to rotate the intake 180 degrees.
+#
+# Michael Schuh
+# January 20, 2018
+
+import math
+import numpy
+import scipy.integrate
+
+pi = math.pi
+pi2 = 2.0 * pi
+rad_to_deg = 180.0 / pi
+inches_to_meters = 0.0254
+lbs_to_kg = 1.0 / 2.2
+newton_to_lbf = 0.224809
+newton_meters_to_ft_lbs = 0.73756
+run_count = 0
+theta_travel = 0.0
+
+def to_deg(angle):
+  return angle * rad_to_deg
+
+def to_rad(angle):
+  return angle / rad_to_deg
+
+def to_rotations(angle):
+  return angle / pi2
+
+def time_derivative(x, t, voltage, c1, c2, c3):
+  global run_count
+  theta, omega = x
+  dxdt = [omega, -c1 * omega + c3 * math.sin(theta) + c2 * voltage]
+  run_count = run_count + 1
+
+  return dxdt
+
+def get_distal_angle(theta_proximal):
+  # For the proximal angle = -50 degrees, the distal angle is -180 degrees
+  # For the proximal angle =  10 degrees, the distal angle is  -90 degrees
+  distal_angle = to_rad(-180.0 - (-50.0 - to_deg(theta_proximal)) * \
+      (180.0 - 90.0) / (50.0 + 10.0))
+  return distal_angle
+
+
+def get_180_degree_time(c1, c2, c3, voltage, gear_ratio, motor_free_speed):
+  global run_count
+  global theta_travel
+
+  if ( True ):
+    # Gravity is assisting the motion.
+    theta_start = 0.0
+    theta_target = pi
+  elif ( False ):
+    # Gravity is assisting the motion.
+    theta_start = 0.0
+    theta_target = -pi
+  elif ( False ):
+    # Gravity is slowing the motion.
+    theta_start = pi
+    theta_target = 0.0
+  elif ( False ):
+    # Gravity is slowing the motion.
+    theta_start = -pi
+    theta_target = 0.0
+  elif ( False ):
+    # This is for the proximal arm motion.
+    theta_start = to_rad(-50.0)
+    theta_target = to_rad(10.0)
+
+  theta_half = 0.5 * (theta_start + theta_target)
+  if theta_start > theta_target:
+    voltage = -voltage
+  theta = theta_start
+  theta_travel = theta_start - theta_target
+  if run_count == 0:
+    print("# Theta Start = %.2f radians End = %.2f Theta travel %.2f "
+          "Theta half = %.2f Voltage = %.2f" % (
+              theta_start, theta_target, theta_travel, theta_half, voltage))
+    print("# Theta Start = %.2f degrees End = %.2f Theta travel %.2f "
+          "Theta half = %.2f Voltage = %.2f" % (
+              to_deg(theta_start), to_deg(theta_target), to_deg(theta_travel),
+              to_deg(theta_half), voltage))
+  omega = 0.0
+  time = 0.0
+  delta_time = 0.01 # time step in seconds
+  for step in range(1, 5000):
+     t = numpy.array([time, time + delta_time])
+     time = time + delta_time
+     x = [theta, omega]
+     angular_acceleration = -c1 * omega + c2 * voltage
+     x_n_plus_1 = scipy.integrate.odeint(time_derivative, x, t,
+                                         args=(voltage, c1, c2, c3))
+     theta, omega = x_n_plus_1[1]
+
+     if ( False ):
+       print("%4d  %8.4f %8.2f          %8.4f          %8.4f    %8.3f    "
+             "%8.3f     %8.3f      %8.3f" % (
+                 step, time, theta, omega, angular_acceleration,
+                 to_rotations(theta), to_rotations(omega),
+                 omega * gear_ratio * 60.0 / pi2,
+                 omega * gear_ratio / motor_free_speed))
+     if theta_start < theta_target:
+       # Angle is increasing through the motion.
+       if theta > theta_half:
+         break
+     else:
+       # Angle is decreasing through the motion.
+       if (theta < theta_half):
+         break
+
+  return 2.0 * time
+
+def main():
+  # m/sec^2 Gravity Constant
+  gravity = 9.8
+  # m/sec^2 Gravity Constant - Use 0.0 for the intake.  It is horizontal.
+  gravity = 0.0
+  # Volts
+  voltage_nominal = 12
+
+  # Vex 775 Pro motor specs from http://banebots.com/p/M2-RS550-120
+  motor_name = "Vex 775 Pro motor specs from http://banebots.com/p/M2-RS550-120"
+  current_stall = 134 # amps stall current
+  current_no_load = 0.7 # amps no load current
+  torque_stall = 710/1000.0 # N-m Stall Torque
+  speed_no_load_rpm = 18730 # RPM no load speed
+
+  if ( True ):
+    # Bag motor from https://www.vexrobotics.com/217-3351.html
+    motor_name = "Bag motor from https://www.vexrobotics.com/217-3351.html"
+    current_stall = 53.0 # amps stall current
+    current_no_load = 1.8 # amps no load current
+    torque_stall = 0.4 # N-m Stall Torque
+    speed_no_load_rpm = 13180.0 # RPM no load speed
+
+  if ( False ):
+    # Mini CIM motor from https://www.vexrobotics.com/217-3371.html
+    motor_name = "Mini CIM motor from https://www.vexrobotics.com/217-3371.html"
+    current_stall = 89.0 # amps stall current
+    current_no_load = 3.0 # amps no load current
+    torque_stall = 1.4 # N-m Stall Torque
+    speed_no_load_rpm = 5840.0 # RPM no load speed
+
+  # How many motors are we using?
+  num_motors = 1
+
+  # Motor values
+  print("# Motor: %s" % (motor_name))
+  print("# Number of motors: %d" % (num_motors))
+  print("# Stall torque: %.1f n-m" % (torque_stall))
+  print("# Stall current: %.1f amps" % (current_stall))
+  print("# No load current: %.1f amps" % (current_no_load))
+  print("# No load speed: %.0f rpm" % (speed_no_load_rpm))
+
+  # Constants from motor values
+  resistance_motor = voltage_nominal / current_stall
+  speed_no_load_rps = speed_no_load_rpm / 60.0 # Revolutions per second no load speed
+  speed_no_load = speed_no_load_rps * 2.0 * pi
+  Kt = num_motors * torque_stall / current_stall # N-m/A torque constant
+  Kv_rpm = speed_no_load_rpm / (voltage_nominal -
+                                resistance_motor * current_no_load)  # rpm/V
+  Kv = Kv_rpm * 2.0 * pi / 60.0  # rpm/V
+
+  # Robot Geometry and physics
+  # m Length of arm connected to the robot base
+  length_proximal_arm = inches_to_meters * 47.34
+  # m Length of arm that holds the cube
+  length_distal_arm = inches_to_meters * 44.0
+  # m Length of intake arm from the pivot point to where the big roller contacts a cube.
+  length_intake_arm =  inches_to_meters * 9.0
+  mass_cube = 6.0 * lbs_to_kg  # Weight of the cube in Kgrams
+  mass_proximal_arm = 5.5 * lbs_to_kg # Weight of proximal arm
+  mass_distal_arm = 3.5 * lbs_to_kg # Weight of distal arm
+  mass_distal = mass_cube + mass_distal_arm
+  mass_proximal = mass_proximal_arm + mass_distal
+  # m Length from arm pivot point to arm CG
+  radius_to_proximal_arm_cg = 22.0 * inches_to_meters
+  # m Length from arm pivot point to arm CG
+  radius_to_distal_arm_cg = 10.0 * inches_to_meters
+
+  radius_to_distal_cg = (length_distal_arm * mass_cube +
+                         radius_to_distal_arm_cg * mass_distal_arm) / \
+                             mass_distal
+  radius_to_proximal_cg = (length_proximal_arm * mass_distal +
+                           radius_to_proximal_arm_cg * mass_proximal_arm) / \
+                               mass_proximal
+  J_cube = length_distal_arm * length_distal_arm*mass_cube
+  # Kg m^2 Moment of inertia of the proximal arm
+  J_proximal_arm = radius_to_proximal_arm_cg * radius_to_proximal_arm_cg * \
+      mass_distal_arm
+  # Kg m^2 Moment of inertia distal arm and cube at end of proximal arm.
+  J_distal_arm_and_cube_at_end_of_proximal_arm = length_proximal_arm * \
+      length_proximal_arm * mass_distal
+  # Kg m^2 Moment of inertia of the distal arm
+  J_distal_arm = radius_to_distal_arm_cg * radius_to_distal_arm_cg * mass_distal_arm
+  # Moment of inertia of the arm with the cube on the end
+  J = J_distal_arm_and_cube_at_end_of_proximal_arm + J_proximal_arm
+  # Intake claw
+  J_intake = 0.295  # Kg m^2 Moment of inertia of intake
+  J = J_intake
+
+  gear_ratio = 140.0  # Guess at the gear ratio
+  gear_ratio = 100.0  # Guess at the gear ratio
+  gear_ratio = 90.0  # Guess at the gear ratio
+
+  error_margine = 1.0
+  voltage = 10.0  # voltage for the motor.  Assuming a loaded robot so not using 12 V.
+  # It might make sense to use a lower motor frees peed when the voltage is not a full 12 Volts.
+  # motor_free_speed = Kv * voltage
+  motor_free_speed = speed_no_load
+
+  print("# Kt = %f N-m/A\n# Kv_rpm = %f rpm/V\n# Kv = %f radians/V" % (Kt, Kv_rpm, Kv))
+  print("# %.2f Ohms Resistance of the motor " % (resistance_motor))
+  print("# %.2f kg Cube weight" % (mass_cube))
+  print("# %.2f kg Proximal Arm mass" % (mass_proximal_arm))
+  print("# %.2f kg Distal Arm mass" % (mass_distal_arm))
+  print("# %.2f kg Distal Arm and Cube weight" % (mass_distal))
+  print("# %.2f m Length from distal arm pivot point to arm CG" % (
+      radius_to_distal_arm_cg))
+  print("# %.2f m Length from distal arm pivot point to arm and cube cg" % (
+      radius_to_distal_cg))
+  print("# %.2f kg-m^2 Moment of inertia of the cube about the arm pivot point" % (J_cube))
+  print("# %.2f m Length from proximal arm pivot point to arm CG" % (radius_to_proximal_arm_cg))
+  print("# %.2f m Length from proximal arm pivot point to arm and cube cg" % (
+      radius_to_proximal_cg))
+  print("# %.2f m  Proximal arm length" % (length_proximal_arm))
+  print("# %.2f m  Distal arm length" % (length_distal_arm))
+
+  print("# %.2f kg-m^2 Moment of inertia of the intake about the intake pivot point" % (
+      J_intake))
+  print("# %.2f kg-m^2 Moment of inertia of the distal arm about the arm pivot point" % (
+      J_distal_arm))
+  print("# %.2f kg-m^2 Moment of inertia of the proximal arm about the arm pivot point" % (
+      J_proximal_arm))
+  print("# %.2f kg-m^2 Moment of inertia of the distal arm and cube mass about "
+        "the proximal arm pivot point" % (
+            J_distal_arm_and_cube_at_end_of_proximal_arm))
+  print("# %.2f kg-m^2 Moment of inertia of the intake the intake pivot point "
+        "(J value used in simulation)" % (J))
+  print("# %d Number of motors" % (num_motors))
+
+  print("# %.2f V Motor voltage" % (voltage))
+  for gear_ratio in range(60, 241, 10):
+    c1 = Kt * gear_ratio * gear_ratio / (Kv * resistance_motor * J)
+    c2 = gear_ratio * Kt / (J * resistance_motor)
+    c3 = radius_to_proximal_cg * mass_proximal * gravity / J
+
+    if ( False ):
+      print("# %.8f 1/sec C1 constant" % (c1))
+      print("# %.2f 1/sec C2 constant" % (c2))
+      print("# %.2f 1/(V sec^2) C3 constant" % (c3))
+      print("# %.2f RPM Free speed at motor voltage" % (voltage * Kv_rpm))
+
+    torque_90_degrees = radius_to_distal_cg * mass_distal * gravity
+    voltage_90_degrees = resistance_motor * torque_90_degrees / (gear_ratio * Kt)
+    torque_peak = gear_ratio * num_motors * torque_stall
+    torque_peak_ft_lbs = torque_peak * newton_meters_to_ft_lbs
+    normal_force = torque_peak / length_intake_arm
+    normal_force_lbf = newton_to_lbf * normal_force
+    time_required = get_180_degree_time(c1, c2, c3, voltage,
+                                        gear_ratio, motor_free_speed)
+    print("Time for %.1f degrees for gear ratio %3.0f is %.2f seconds.  "
+          "Peak (stall) torque %3.0f nm %3.0f ft-lb Normal force at intake "
+          "end %3.0f N %2.0f lbf" % \
+      (to_deg(theta_travel), gear_ratio, time_required,
+       torque_peak, torque_peak_ft_lbs, normal_force, normal_force_lbf))
+
+if __name__ == '__main__':
+  main()