Refactor linear_system out of 2017 intake

So we can reuse it!

Change-Id: I0583dbd1fd1a8765468f861a9acba0194aaa8ef6
diff --git a/frc971/control_loops/python/BUILD b/frc971/control_loops/python/BUILD
index c0b71f7..3fa425c 100644
--- a/frc971/control_loops/python/BUILD
+++ b/frc971/control_loops/python/BUILD
@@ -112,3 +112,16 @@
         "@matplotlib",
     ],
 )
+
+py_library(
+    name = "linear_system",
+    srcs = ["linear_system.py"],
+    restricted_to = ["//tools:k8"],
+    visibility = ["//visibility:public"],
+    deps = [
+        ":controls",
+        "//aos/util:py_trapezoid_profile",
+        "//frc971/control_loops:python_init",
+        "@matplotlib",
+    ],
+)
diff --git a/frc971/control_loops/python/control_loop.py b/frc971/control_loops/python/control_loop.py
index 2ef2ece..74cd389 100644
--- a/frc971/control_loops/python/control_loop.py
+++ b/frc971/control_loops/python/control_loop.py
@@ -246,6 +246,11 @@
     """
     self._name = name
 
+  @property
+  def name(self):
+    """Returns the name"""
+    return self._name
+
   def ContinuousToDiscrete(self, A_continuous, B_continuous, dt):
     """Calculates the discrete time values for A and B.
 
@@ -531,6 +536,40 @@
     self.Kt = self.stall_torque / self.stall_current
 
 
+class NMotor(object):
+    def __init__(self, motor, n):
+        """Gangs together n motors."""
+        self.motor = motor
+        self.stall_torque = motor.stall_torque * n
+        self.stall_current = motor.stall_current * n
+        self.free_speed = motor.free_speed
+
+        self.free_current = motor.free_current * n
+        self.resistance = motor.resistance / n
+        self.Kv = motor.Kv
+        self.Kt = motor.Kt
+
+
+class Vex775Pro(object):
+    def __init__(self):
+        # Stall Torque in N m
+        self.stall_torque = 0.71
+        # Stall Current in Amps
+        self.stall_current = 134.0
+        # Free Speed in rad/s
+        self.free_speed = 18730.0 / 60.0 * 2.0 * numpy.pi
+        # Free Current in Amps
+        self.free_current = 0.7
+        # Resistance of the motor
+        self.resistance = 12.0 / self.stall_current
+        # Motor velocity constant
+        self.Kv = (self.free_speed / (12.0 - self.resistance * self.free_current))
+        # Torque constant
+        self.Kt = self.stall_torque / self.stall_current
+        # Motor inertia in kg m^2
+        self.motor_inertia = 0.00001187
+
+
 class BAG(object):
   # BAG motor specs available at http://motors.vex.com/vexpro-motors/bag-motor
   def __init__(self):
diff --git a/frc971/control_loops/python/linear_system.py b/frc971/control_loops/python/linear_system.py
new file mode 100755
index 0000000..21fa4ec
--- /dev/null
+++ b/frc971/control_loops/python/linear_system.py
@@ -0,0 +1,392 @@
+#!/usr/bin/python
+
+from aos.util.trapezoid_profile import TrapezoidProfile
+from frc971.control_loops.python import control_loop
+from frc971.control_loops.python import controls
+import numpy
+import sys
+from matplotlib import pylab
+import glog
+
+
+class LinearSystemParams(object):
+    def __init__(self,
+                 name,
+                 motor,
+                 G,
+                 radius,
+                 mass,
+                 q_pos,
+                 q_vel,
+                 kalman_q_pos,
+                 kalman_q_vel,
+                 kalman_q_voltage,
+                 kalman_r_position,
+                 dt=0.005):
+        self.name = name
+        self.motor = motor
+        self.G = G
+        self.radius = radius
+        self.mass = mass
+        self.q_pos = q_pos
+        self.q_vel = q_vel
+        self.kalman_q_pos = kalman_q_pos
+        self.kalman_q_vel = kalman_q_vel
+        self.kalman_q_voltage = kalman_q_voltage
+        self.kalman_r_position = kalman_r_position
+        self.dt = dt
+
+
+class LinearSystem(control_loop.ControlLoop):
+    def __init__(self, params, name='LinearSystem'):
+        super(LinearSystem, self).__init__(name)
+        self.params = params
+
+        self.motor = params.motor
+
+        # Gear ratio
+        self.G = params.G
+        self.radius = params.radius
+
+        # 5.4 kg of moving mass for the linear_system
+        self.mass = params.mass + self.motor.motor_inertia / (
+            (self.G * self.radius)**2.0)
+
+        # Control loop time step
+        self.dt = params.dt
+
+        # State is [position, velocity]
+        # Input is [Voltage]
+        C1 = self.motor.Kt / (self.G * self.G * self.radius * self.radius *
+                              self.motor.resistance * self.mass *
+                              self.motor.Kv)
+        C2 = self.motor.Kt / (self.G * self.radius * self.motor.resistance *
+                              self.mass)
+
+        self.A_continuous = numpy.matrix([[0, 1], [0, -C1]])
+
+        # Start with the unmodified input
+        self.B_continuous = numpy.matrix([[0], [C2]])
+        glog.debug(repr(self.A_continuous))
+        glog.debug(repr(self.B_continuous))
+
+        self.C = numpy.matrix([[1, 0]])
+        self.D = numpy.matrix([[0]])
+
+        self.A, self.B = self.ContinuousToDiscrete(self.A_continuous,
+                                                   self.B_continuous, self.dt)
+
+        controllability = controls.ctrb(self.A, self.B)
+        glog.debug('Controllability of %d',
+                   numpy.linalg.matrix_rank(controllability))
+        glog.debug('Mass: %f', self.mass)
+        glog.debug('Stall force: %f', self.motor.stall_torque / self.G / self.radius)
+        glog.debug('Stall acceleration: %f', self.motor.stall_torque / self.G /
+                   self.radius / self.mass)
+
+        glog.debug('Free speed is %f',
+                   -self.B_continuous[1, 0] / self.A_continuous[1, 1] * 12.0)
+
+        self.Q = numpy.matrix([[(1.0 / (self.params.q_pos**2.0)), 0.0],
+                               [0.0, (1.0 / (self.params.q_vel**2.0))]])
+
+        self.R = numpy.matrix([[(1.0 / (12.0**2.0))]])
+        self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
+
+        q_pos_ff = 0.005
+        q_vel_ff = 1.0
+        self.Qff = numpy.matrix([[(1.0 / (q_pos_ff**2.0)), 0.0],
+                                 [0.0, (1.0 / (q_vel_ff**2.0))]])
+
+        self.Kff = controls.TwoStateFeedForwards(self.B, self.Qff)
+
+        glog.debug('K %s', repr(self.K))
+        glog.debug('Poles are %s',
+                   repr(numpy.linalg.eig(self.A - self.B * self.K)[0]))
+
+        self.Q = numpy.matrix([[(self.params.kalman_q_pos**2.0), 0.0],
+                               [0.0, (self.params.kalman_q_vel**2.0)]])
+
+        self.R = numpy.matrix([[(self.params.kalman_r_position**2.0)]])
+
+        self.KalmanGain, self.Q_steady = controls.kalman(
+            A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
+
+        glog.debug('Kal %s', repr(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 IntegralLinearSystem(LinearSystem):
+    def __init__(self, params, name='IntegralLinearSystem'):
+        super(IntegralLinearSystem, self).__init__(params, name=name)
+
+        self.kalman_q_voltage = params.kalman_q_voltage
+
+        self.A_continuous_unaugmented = self.A_continuous
+        self.B_continuous_unaugmented = self.B_continuous
+
+        self.A_continuous = numpy.matrix(numpy.zeros((3, 3)))
+        self.A_continuous[0:2, 0:2] = self.A_continuous_unaugmented
+        self.A_continuous[0:2, 2] = self.B_continuous_unaugmented
+
+        self.B_continuous = numpy.matrix(numpy.zeros((3, 1)))
+        self.B_continuous[0:2, 0] = self.B_continuous_unaugmented
+
+        self.C_unaugmented = self.C
+        self.C = numpy.matrix(numpy.zeros((1, 3)))
+        self.C[0:1, 0:2] = self.C_unaugmented
+
+        self.A, self.B = self.ContinuousToDiscrete(self.A_continuous,
+                                                   self.B_continuous, self.dt)
+
+        self.Q = numpy.matrix(
+            [[(self.params.kalman_q_pos**2.0), 0.0, 0.0],
+             [0.0, (self.params.kalman_q_vel**2.0), 0.0],
+             [0.0, 0.0, (self.params.kalman_q_voltage**2.0)]])
+
+        self.R = numpy.matrix([[(self.params.kalman_r_position**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.K_unaugmented = self.K
+        self.K = numpy.matrix(numpy.zeros((1, 3)))
+        self.K[0, 0:2] = self.K_unaugmented
+        self.K[0, 2] = 1
+
+        self.Kff = numpy.concatenate(
+            (self.Kff, numpy.matrix(numpy.zeros((1, 1)))), axis=1)
+
+        self.InitializeState()
+
+
+def RunTest(plant,
+            end_goal,
+            controller,
+            observer=None,
+            duration=1.0,
+            use_profile=True,
+            kick_time=0.5,
+            kick_magnitude=0.0,
+            max_velocity=0.3):
+    """Runs the plant with an initial condition and goal.
+
+    Args:
+      plant: plant object to use.
+      end_goal: end_goal state.
+      controller: Intake object to get K from, or None if we should
+          use plant.
+      observer: Intake object to use for the observer, or None if we should
+          use the actual state.
+      duration: float, time in seconds to run the simulation for.
+      kick_time: float, time in seconds to kick the robot.
+      kick_magnitude: float, disturbance in volts to apply.
+      max_velocity: float, the max speed in m/s to profile.
+    """
+    t_plot = []
+    x_plot = []
+    v_plot = []
+    a_plot = []
+    x_goal_plot = []
+    v_goal_plot = []
+    x_hat_plot = []
+    u_plot = []
+    offset_plot = []
+
+    if controller is None:
+        controller = plant
+
+    vbat = 12.0
+
+    goal = numpy.concatenate(
+        (plant.X, numpy.matrix(numpy.zeros((1, 1)))), axis=0)
+
+    profile = TrapezoidProfile(plant.dt)
+    profile.set_maximum_acceleration(10.0)
+    profile.set_maximum_velocity(max_velocity)
+    profile.SetGoal(goal[0, 0])
+
+    U_last = numpy.matrix(numpy.zeros((1, 1)))
+    iterations = int(duration / plant.dt)
+    for i in xrange(iterations):
+        t = i * plant.dt
+        observer.Y = plant.Y
+        observer.CorrectObserver(U_last)
+
+        offset_plot.append(observer.X_hat[2, 0])
+        x_hat_plot.append(observer.X_hat[0, 0])
+
+        next_goal = numpy.concatenate(
+            (profile.Update(end_goal[0, 0], end_goal[1, 0]),
+             numpy.matrix(numpy.zeros((1, 1)))),
+            axis=0)
+
+        ff_U = controller.Kff * (next_goal - observer.A * goal)
+
+        if use_profile:
+            U_uncapped = controller.K * (goal - observer.X_hat) + ff_U
+            x_goal_plot.append(goal[0, 0])
+            v_goal_plot.append(goal[1, 0])
+        else:
+            U_uncapped = controller.K * (end_goal - observer.X_hat)
+            x_goal_plot.append(end_goal[0, 0])
+            v_goal_plot.append(end_goal[1, 0])
+
+        U = U_uncapped.copy()
+        U[0, 0] = numpy.clip(U[0, 0], -vbat, vbat)
+        x_plot.append(plant.X[0, 0])
+
+        if v_plot:
+            last_v = v_plot[-1]
+        else:
+            last_v = 0
+
+        v_plot.append(plant.X[1, 0])
+        a_plot.append((v_plot[-1] - last_v) / plant.dt)
+
+        u_offset = 0.0
+        if t >= kick_time:
+            u_offset = kick_magnitude
+        plant.Update(U + u_offset)
+
+        observer.PredictObserver(U)
+
+        t_plot.append(t)
+        u_plot.append(U[0, 0])
+
+        ff_U -= U_uncapped - U
+        goal = controller.A * goal + controller.B * ff_U
+
+        if U[0, 0] != U_uncapped[0, 0]:
+            profile.MoveCurrentState(
+                numpy.matrix([[goal[0, 0]], [goal[1, 0]]]))
+
+    glog.debug('Time: %f', t_plot[-1])
+    glog.debug('goal_error %s', repr(end_goal - goal))
+    glog.debug('error %s', repr(observer.X_hat - end_goal))
+
+    pylab.subplot(3, 1, 1)
+    pylab.plot(t_plot, x_plot, label='x')
+    pylab.plot(t_plot, x_hat_plot, label='x_hat')
+    pylab.plot(t_plot, x_goal_plot, label='x_goal')
+    pylab.legend()
+
+    pylab.subplot(3, 1, 2)
+    pylab.plot(t_plot, u_plot, label='u')
+    pylab.plot(t_plot, offset_plot, label='voltage_offset')
+    pylab.legend()
+
+    pylab.subplot(3, 1, 3)
+    pylab.plot(t_plot, a_plot, label='a')
+    pylab.legend()
+
+    pylab.show()
+
+
+def PlotStep(params, R):
+    """Plots a step move to the goal.
+
+    Args:
+      R: numpy.matrix(2, 1), the goal"""
+    plant = LinearSystem(params, params.name)
+    controller = IntegralLinearSystem(params, params.name)
+    observer = IntegralLinearSystem(params, params.name)
+
+    # Test moving the system.
+    initial_X = numpy.matrix([[0.0], [0.0]])
+    augmented_R = numpy.matrix(numpy.zeros((3, 1)))
+    augmented_R[0:2, :] = R
+    RunTest(
+        plant,
+        end_goal=augmented_R,
+        controller=controller,
+        observer=observer,
+        duration=2.0,
+        use_profile=False,
+        kick_time=1.0,
+        kick_magnitude=0.0)
+
+
+def PlotKick(params, R):
+    """Plots a step motion with a kick at 1.0 seconds.
+
+    Args:
+      R: numpy.matrix(2, 1), the goal"""
+    plant = LinearSystem(params, params.name)
+    controller = IntegralLinearSystem(params, params.name)
+    observer = IntegralLinearSystem(params, params.name)
+
+    # Test moving the system.
+    initial_X = numpy.matrix([[0.0], [0.0]])
+    augmented_R = numpy.matrix(numpy.zeros((3, 1)))
+    augmented_R[0:2, :] = R
+    RunTest(
+        plant,
+        end_goal=augmented_R,
+        controller=controller,
+        observer=observer,
+        duration=2.0,
+        use_profile=False,
+        kick_time=1.0,
+        kick_magnitude=2.0)
+
+
+def PlotMotion(params, R, max_velocity=0.3):
+    """Plots a trapezoidal motion.
+
+    Args:
+      R: numpy.matrix(2, 1), the goal,
+      max_velocity: float, The max velocity of the profile.
+    """
+    plant = LinearSystem(params, params.name)
+    controller = IntegralLinearSystem(params, params.name)
+    observer = IntegralLinearSystem(params, params.name)
+
+    # Test moving the system.
+    initial_X = numpy.matrix([[0.0], [0.0]])
+    augmented_R = numpy.matrix(numpy.zeros((3, 1)))
+    augmented_R[0:2, :] = R
+    RunTest(
+        plant,
+        end_goal=augmented_R,
+        controller=controller,
+        observer=observer,
+        duration=2.0,
+        use_profile=True,
+        max_velocity=max_velocity)
+
+
+def WriteLinearSystem(params, plant_files, controller_files, year_namespaces):
+    """Writes out the constants for a linear system to a file.
+
+    Args:
+      params: LinearSystemParams, the parameters defining the system.
+      plant_files: list of strings, the cc and h files for the plant.
+      controller_files: list of strings, the cc and h files for the integral
+        controller.
+      year_namespaces: list of strings, the namespace list to use.
+    """
+    # Write the generated constants out to a file.
+    linear_system = LinearSystem(params, params.name)
+    loop_writer = control_loop.ControlLoopWriter(
+        linear_system.name, [linear_system], namespaces=year_namespaces)
+    loop_writer.AddConstant(
+        control_loop.Constant('kFreeSpeed', '%f', linear_system.motor.
+                              free_speed / (2.0 * numpy.pi)))
+    loop_writer.AddConstant(
+        control_loop.Constant('kOutputRatio', '%f', linear_system.G *
+                              linear_system.radius))
+    loop_writer.Write(plant_files[0], plant_files[1])
+
+    integral_linear_system = IntegralLinearSystem(params,
+                                                  'Integral' + params.name)
+    integral_loop_writer = control_loop.ControlLoopWriter(
+        integral_linear_system.name, [integral_linear_system],
+        namespaces=year_namespaces)
+    integral_loop_writer.Write(controller_files[0], controller_files[1])
diff --git a/y2017/control_loops/python/BUILD b/y2017/control_loops/python/BUILD
index 5d7a002..3f23bde 100644
--- a/y2017/control_loops/python/BUILD
+++ b/y2017/control_loops/python/BUILD
@@ -86,11 +86,9 @@
     restricted_to = ["//tools:k8"],
     deps = [
         ":python_init",
-        "//aos/util:py_trapezoid_profile",
         "//external:python-gflags",
         "//external:python-glog",
-        "//frc971/control_loops/python:controls",
-        "@matplotlib",
+        "//frc971/control_loops/python:linear_system",
     ],
 )
 
diff --git a/y2017/control_loops/python/intake.py b/y2017/control_loops/python/intake.py
index 64998c7..015fdfa 100755
--- a/y2017/control_loops/python/intake.py
+++ b/y2017/control_loops/python/intake.py
@@ -1,318 +1,51 @@
 #!/usr/bin/python
 
-from aos.util.trapezoid_profile import TrapezoidProfile
 from frc971.control_loops.python import control_loop
-from frc971.control_loops.python import controls
+from frc971.control_loops.python import linear_system
 import numpy
 import sys
-from matplotlib import pylab
 import gflags
 import glog
 
 FLAGS = gflags.FLAGS
 
 try:
-  gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+    gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
 except gflags.DuplicateFlagError:
-  pass
+    pass
 
-class Intake(control_loop.ControlLoop):
-  def __init__(self, name='Intake'):
-    super(Intake, self).__init__(name)
-    # Stall Torque in N m
-    self.stall_torque = 0.71
-    # Stall Current in Amps
-    self.stall_current = 134.0
-    self.free_speed_rpm = 18730.0
-    # Free Speed in rotations/second.
-    self.free_speed = self.free_speed_rpm / 60.0
-    # Free Current in Amps
-    self.free_current = 0.7
-
-    # Resistance of the motor
-    self.R = 12.0 / self.stall_current
-    # Motor velocity constant
-    self.Kv = ((self.free_speed * 2.0 * numpy.pi) /
-               (12.0 - self.R * self.free_current))
-    # Torque constant
-    self.Kt = self.stall_torque / self.stall_current
-
+kIntake = linear_system.LinearSystemParams(
+    name='Intake',
+    motor=control_loop.Vex775Pro(),
     # (1 / 35.0) * (20.0 / 40.0) -> 16 tooth sprocket on #25 chain
-    # Gear ratio
-    self.G = (1.0 / 35.0) * (20.0 / 40.0)
-    self.r = 16.0 * 0.25 / (2.0 * numpy.pi) * 0.0254
-
-    # Motor inertia in kg m^2
-    self.motor_inertia = 0.00001187
-
-    # 5.4 kg of moving mass for the intake
-    self.mass = 5.4 + self.motor_inertia / ((self.G * self.r) ** 2.0)
-
-    # Control loop time step
-    self.dt = 0.005
-
-    # State is [position, velocity]
-    # Input is [Voltage]
-
-    C1 = self.Kt / (self.G * self.G * self.r * self.r * self.R  * self.mass * self.Kv)
-    C2 = self.Kt / (self.G * self.r * self.R  * self.mass)
-
-    self.A_continuous = numpy.matrix(
-        [[0, 1],
-         [0, -C1]])
-
-    # Start with the unmodified input
-    self.B_continuous = numpy.matrix(
-        [[0],
-         [C2]])
-    glog.debug(repr(self.A_continuous))
-    glog.debug(repr(self.B_continuous))
-
-    self.C = numpy.matrix([[1, 0]])
-    self.D = numpy.matrix([[0]])
-
-    self.A, self.B = self.ContinuousToDiscrete(
-        self.A_continuous, self.B_continuous, self.dt)
-
-    controllability = controls.ctrb(self.A, self.B)
-
-    glog.debug('Free speed is %f',
-               -self.B_continuous[1, 0] / self.A_continuous[1, 1] * 12.0)
-
-    q_pos = 0.015
-    q_vel = 0.3
-    self.Q = numpy.matrix([[(1.0 / (q_pos ** 2.0)), 0.0],
-                           [0.0, (1.0 / (q_vel ** 2.0))]])
-
-    self.R = numpy.matrix([[(1.0 / (12.0 ** 2.0))]])
-    self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
-
-    q_pos_ff = 0.005
-    q_vel_ff = 1.0
-    self.Qff = numpy.matrix([[(1.0 / (q_pos_ff ** 2.0)), 0.0],
-                             [0.0, (1.0 / (q_vel_ff ** 2.0))]])
-
-    self.Kff = controls.TwoStateFeedForwards(self.B, self.Qff)
-
-    glog.debug('K %s', repr(self.K))
-    glog.debug('Poles are %s',
-              repr(numpy.linalg.eig(self.A - self.B * self.K)[0]))
-
-    q_pos = 0.10
-    q_vel = 1.65
-    self.Q = numpy.matrix([[(q_pos ** 2.0), 0.0],
-                           [0.0, (q_vel ** 2.0)]])
-
-    r_volts = 0.025
-    self.R = numpy.matrix([[(r_volts ** 2.0)]])
-
-    self.KalmanGain, self.Q_steady = controls.kalman(
-        A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
-
-    glog.debug('Kal %s', repr(self.KalmanGain))
-    self.L = self.A * self.KalmanGain
-    glog.debug('KalL is %s', repr(self.L))
-
-    # 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 IntegralIntake(Intake):
-  def __init__(self, name='IntegralIntake'):
-    super(IntegralIntake, self).__init__(name=name)
-
-    self.A_continuous_unaugmented = self.A_continuous
-    self.B_continuous_unaugmented = self.B_continuous
-
-    self.A_continuous = numpy.matrix(numpy.zeros((3, 3)))
-    self.A_continuous[0:2, 0:2] = self.A_continuous_unaugmented
-    self.A_continuous[0:2, 2] = self.B_continuous_unaugmented
-
-    self.B_continuous = numpy.matrix(numpy.zeros((3, 1)))
-    self.B_continuous[0:2, 0] = self.B_continuous_unaugmented
-
-    self.C_unaugmented = self.C
-    self.C = numpy.matrix(numpy.zeros((1, 3)))
-    self.C[0:1, 0:2] = self.C_unaugmented
-
-    self.A, self.B = self.ContinuousToDiscrete(
-        self.A_continuous, self.B_continuous, self.dt)
-
-    q_pos = 0.12
-    q_vel = 2.00
-    q_voltage = 40.0
-    self.Q = numpy.matrix([[(q_pos ** 2.0), 0.0, 0.0],
-                           [0.0, (q_vel ** 2.0), 0.0],
-                           [0.0, 0.0, (q_voltage ** 2.0)]])
-
-    r_pos = 0.05
-    self.R = numpy.matrix([[(r_pos ** 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
-
-    self.K_unaugmented = self.K
-    self.K = numpy.matrix(numpy.zeros((1, 3)))
-    self.K[0, 0:2] = self.K_unaugmented
-    self.K[0, 2] = 1
-
-    self.Kff = numpy.concatenate((self.Kff, numpy.matrix(numpy.zeros((1, 1)))), axis=1)
-
-    self.InitializeState()
-
-class ScenarioPlotter(object):
-  def __init__(self):
-    # Various lists for graphing things.
-    self.t = []
-    self.x = []
-    self.v = []
-    self.a = []
-    self.x_hat = []
-    self.u = []
-    self.offset = []
-
-  def run_test(self, intake, end_goal,
-             controller_intake,
-             observer_intake=None,
-             iterations=200):
-    """Runs the intake plant with an initial condition and goal.
-
-      Args:
-        intake: intake object to use.
-        end_goal: end_goal state.
-        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.
-        iterations: Number of timesteps to run the model for.
-    """
-
-    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
-
-    goal = numpy.concatenate((intake.X, numpy.matrix(numpy.zeros((1, 1)))), axis=0)
-
-    profile = TrapezoidProfile(intake.dt)
-    profile.set_maximum_acceleration(10.0)
-    profile.set_maximum_velocity(0.3)
-    profile.SetGoal(goal[0, 0])
-
-    U_last = numpy.matrix(numpy.zeros((1, 1)))
-    for i in xrange(iterations):
-      observer_intake.Y = intake.Y
-      observer_intake.CorrectObserver(U_last)
-
-      self.offset.append(observer_intake.X_hat[2, 0])
-      self.x_hat.append(observer_intake.X_hat[0, 0])
-
-      next_goal = numpy.concatenate(
-          (profile.Update(end_goal[0, 0], end_goal[1, 0]),
-           numpy.matrix(numpy.zeros((1, 1)))),
-          axis=0)
-
-      ff_U = controller_intake.Kff * (next_goal - observer_intake.A * goal)
-
-      U_uncapped = controller_intake.K * (goal - observer_intake.X_hat) + ff_U
-      U_uncapped = controller_intake.K * (end_goal - observer_intake.X_hat)
-      U = U_uncapped.copy()
-      U[0, 0] = numpy.clip(U[0, 0], -vbat, vbat)
-      self.x.append(intake.X[0, 0])
-
-      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)
-
-      offset = 0.0
-      if i > 100:
-        offset = 2.0
-      intake.Update(U + offset)
-
-      observer_intake.PredictObserver(U)
-
-      self.t.append(initial_t + i * intake.dt)
-      self.u.append(U[0, 0])
-
-      ff_U -= U_uncapped - U
-      goal = controller_intake.A * goal + controller_intake.B * ff_U
-
-      if U[0, 0] != U_uncapped[0, 0]:
-        profile.MoveCurrentState(
-            numpy.matrix([[goal[0, 0]], [goal[1, 0]]]))
-
-    glog.debug('Time: %f', self.t[-1])
-    glog.debug('goal_error %s', repr(end_goal - goal))
-    glog.debug('error %s', repr(observer_intake.X_hat - end_goal))
-
-  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()
-
-    pylab.subplot(3, 1, 2)
-    pylab.plot(self.t, self.u, label='u')
-    pylab.plot(self.t, self.offset, label='voltage_offset')
-    pylab.legend()
-
-    pylab.subplot(3, 1, 3)
-    pylab.plot(self.t, self.a, label='a')
-    pylab.legend()
-
-    pylab.show()
+    G=(1.0 / 35.0) * (20.0 / 40.0),
+    radius=16.0 * 0.25 / (2.0 * numpy.pi) * 0.0254,
+    mass=5.4,
+    q_pos=0.015,
+    q_vel=0.3,
+    kalman_q_pos=0.12,
+    kalman_q_vel=2.00,
+    kalman_q_voltage=40.0,
+    kalman_r_position=0.05)
 
 
 def main(argv):
-  scenario_plotter = ScenarioPlotter()
+    if FLAGS.plot:
+        R = numpy.matrix([[0.1], [0.0]])
+        linear_system.PlotMotion(kIntake, R)
 
-  intake = Intake()
-  intake_controller = IntegralIntake()
-  observer_intake = IntegralIntake()
+    # 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 = ['y2017', 'control_loops', 'superstructure', 'intake']
+        linear_system.WriteLinearSystem(kIntake, argv[1:3], argv[3:5],
+                                        namespaces)
 
-  # Test moving the intake with constant separation.
-  initial_X = numpy.matrix([[0.0], [0.0]])
-  R = numpy.matrix([[0.1], [0.0], [0.0]])
-  scenario_plotter.run_test(intake, end_goal=R,
-                            controller_intake=intake_controller,
-                            observer_intake=observer_intake, iterations=400)
-
-  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 = ['y2017', 'control_loops', 'superstructure', 'intake']
-    intake = Intake('Intake')
-    loop_writer = control_loop.ControlLoopWriter('Intake', [intake],
-                                                 namespaces=namespaces)
-    loop_writer.AddConstant(control_loop.Constant('kFreeSpeed', '%f',
-                                                  intake.free_speed))
-    loop_writer.AddConstant(control_loop.Constant('kOutputRatio', '%f',
-                                                  intake.G * intake.r))
-    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__':
-  argv = FLAGS(sys.argv)
-  glog.init()
-  sys.exit(main(argv))
+    argv = FLAGS(sys.argv)
+    glog.init()
+    sys.exit(main(argv))