Merge "Fix nullptr dereference in dlqr()" into main
diff --git a/documentation/tutorials/getting-started.md b/documentation/tutorials/getting-started.md
index 8e04fcb..fb8ddaf 100644
--- a/documentation/tutorials/getting-started.md
+++ b/documentation/tutorials/getting-started.md
@@ -80,7 +80,7 @@
 
 ## Running the Code
 
-To run the code you'll need to download the repository from [gerrit](https://software.frc971.org/gerrit/admin/repos/971-Robot-Code), make sure to select ssh and not http.
+To run the code you'll need to download the repository from [gerrit](https://software.frc971.org/gerrit/admin/repos/971-Robot-Code), make sure to select ssh and not http. Click on SSH, and clone with commit message hook. Copy the command, and run it locally on terminal.
 To learn more about git, open a terminal and run `man git`, or see [git(1)](https://manpages.debian.org/buster/git-man/git.1.en.html) (especially the NOTES section).
 
 Once the repositoy is selected you'll want to make sure to configure your name, email on git. This is required to ensure you're following the [contributing guidelines above](#contributing). You can do this by running these following commands:
diff --git a/frc971/control_loops/swerve/BUILD b/frc971/control_loops/swerve/BUILD
index f51ba04..224b8e8 100644
--- a/frc971/control_loops/swerve/BUILD
+++ b/frc971/control_loops/swerve/BUILD
@@ -144,12 +144,14 @@
         "dynamics.cc",
         "dynamics.h",
         "dynamics.py",
+        "dynamics_constants.py",
     ],
     args = [
         "--output_base=$(BINDIR)/",
         "--cc_output_path=$(location :dynamics.cc)",
         "--h_output_path=$(location :dynamics.h)",
         "--casadi_py_output_path=$(location :dynamics.py)",
+        "--constants_output_path=$(location :dynamics_constants.py)",
     ],
     tool = ":generate_physics",
 )
@@ -204,10 +206,10 @@
 py_library(
     name = "jax_dynamics",
     srcs = [
+        "dynamics_constants.py",
         "jax_dynamics.py",
     ],
     deps = [
-        ":dynamics",
         "//frc971/control_loops/python:controls",
         "@pip//jax",
     ],
@@ -225,11 +227,15 @@
     main = "physics_test.py",
     target_compatible_with = ["@platforms//cpu:x86_64"],
     deps = [
+        ":casadi_velocity_mpc_lib",
         ":dynamics",
         ":jax_dynamics",
         ":physics_test_utils",
+        "@pip//absl_py",
         "@pip//casadi",
+        "@pip//matplotlib",
         "@pip//numpy",
+        "@pip//pygobject",
         "@pip//scipy",
     ],
 )
@@ -246,12 +252,28 @@
     main = "physics_test.py",
     target_compatible_with = ["@platforms//cpu:x86_64"],
     deps = [
+        ":casadi_velocity_mpc_lib",
         ":dynamics",
         ":jax_dynamics",
         ":physics_test_utils",
+        "@pip//absl_py",
+        "@pip//casadi",
+        "@pip//matplotlib",
+        "@pip//numpy",
+        "@pip//pygobject",
+        "@pip//scipy",
+    ],
+)
+
+py_binary(
+    name = "casadi_velocity_mpc_lib",
+    srcs = [
+        "casadi_velocity_mpc_lib.py",
+    ],
+    deps = [
+        ":dynamics",
         "@pip//casadi",
         "@pip//numpy",
-        "@pip//scipy",
     ],
 )
 
@@ -261,9 +283,8 @@
         "casadi_velocity_mpc.py",
     ],
     deps = [
-        ":dynamics",
+        ":casadi_velocity_mpc_lib",
         "@pip//absl_py",
-        "@pip//casadi",
         "@pip//matplotlib",
         "@pip//numpy",
         "@pip//pygobject",
@@ -271,6 +292,33 @@
     ],
 )
 
+py_binary(
+    name = "experience_collector",
+    srcs = [
+        "experience_collector.py",
+    ],
+    deps = [
+        ":casadi_velocity_mpc_lib",
+        ":jax_dynamics",
+        "//frc971/control_loops/swerve/velocity_controller:physics",
+        "@pip//absl_py",
+        "@pip//matplotlib",
+        "@pip//numpy",
+        "@pip//pygobject",
+        "@pip//scipy",
+        "@pip//tensorflow",
+    ],
+)
+
+py_binary(
+    name = "multi_experience_collector",
+    srcs = ["multi_experience_collector.py"],
+    data = [":experience_collector"],
+    deps = [
+        "@pip//absl_py",
+    ],
+)
+
 py_library(
     name = "physics_test_utils",
     srcs = [
diff --git a/frc971/control_loops/swerve/casadi_velocity_mpc.py b/frc971/control_loops/swerve/casadi_velocity_mpc.py
index 517de5a..54e33f1 100644
--- a/frc971/control_loops/swerve/casadi_velocity_mpc.py
+++ b/frc971/control_loops/swerve/casadi_velocity_mpc.py
@@ -1,6 +1,7 @@
 #!/usr/bin/env python3
 
 from frc971.control_loops.swerve import dynamics
+from frc971.control_loops.swerve.casadi_velocity_mpc_lib import MPC
 import pickle
 import matplotlib.pyplot as pyplot
 import matplotlib
@@ -23,297 +24,6 @@
 flags.DEFINE_bool('pickle', False, 'Write optimization results.')
 flags.DEFINE_string('outputdir', None, 'Directory to write problem results to')
 
-matplotlib.use("GTK3Agg")
-
-# Full print level on ipopt. Piping to a file and using a filter or search method is suggested
-# grad_x prints out the gradient at each iteration in the following sequence: U0, X1, U1, etc.
-full_debug = False
-
-
-class MPC(object):
-
-    def __init__(self, solver='fatrop'):
-        self.fdot = dynamics.swerve_full_dynamics(
-            casadi.SX.sym("X", dynamics.NUM_STATES, 1),
-            casadi.SX.sym("U", 8, 1))
-        self.velocity_fdot = dynamics.velocity_swerve_physics(
-            casadi.SX.sym("X", dynamics.NUM_VELOCITY_STATES, 1),
-            casadi.SX.sym("U", 8, 1))
-
-        self.wrapped_swerve_physics = lambda X, U: numpy.array(self.fdot(X, U))
-
-        self.dt = 0.005
-
-        # TODO(austin): Do we need a disturbance torque per module to account for friction?
-        # Do it only in the observer/post?
-
-        self.force = [
-            dynamics.F(i, casadi.SX.sym("X", 25, 1), casadi.SX.sym("U", 8, 1))
-            for i in range(4)
-        ]
-        self.force_vel = [
-            dynamics.F_vel(i,
-                           casadi.SX.sym("X", dynamics.NUM_VELOCITY_STATES, 1),
-                           casadi.SX.sym("U", 8, 1)) for i in range(4)
-        ]
-        self.slip_angle = [
-            dynamics.slip_angle(i, casadi.SX.sym("X", 25, 1),
-                                casadi.SX.sym("U", 8, 1)) for i in range(4)
-        ]
-        self.mounting_location = [
-            dynamics.mounting_location(
-                i, casadi.SX.sym("X", dynamics.NUM_VELOCITY_STATES, 1),
-                casadi.SX.sym("U", 8, 1)) for i in range(4)
-        ]
-        self.torque_cross = self.torque_cross_func(casadi.SX.sym("r", 2, 1),
-                                                   casadi.SX.sym("F", 2, 1))
-        self.force_cross = self.force_cross_func(casadi.SX.sym("Tau", 1, 1),
-                                                 casadi.SX.sym("r", 2, 1))
-        self.next_X = self.make_physics()
-        self.cost = self.make_cost()
-
-        self.N = 200
-
-        # Start with an empty nonlinear program.
-        self.w = []
-        self.lbw = []
-        self.ubw = []
-        J = 0
-        self.g = []
-        self.lbg = []
-        self.ubg = []
-
-        self.X0 = casadi.MX.sym('X0', dynamics.NUM_VELOCITY_STATES)
-
-        # We care about the linear and angular velocities only.
-        self.R = casadi.MX.sym('R', 3)
-
-        # Make Xn and U for each step.  fatrop wants us to interleave the control variables and
-        # states so that it can produce a banded/structured problem which it can solve a lot
-        # faster.
-        Xn_variables = []
-        U_variables = []
-        for i in range(self.N):
-            U_variables.append(casadi.MX.sym(f'U{i}', 8))
-
-            if i == 0:
-                continue
-
-            Xn_variables.append(
-                casadi.MX.sym(f'X{i}', dynamics.NUM_VELOCITY_STATES))
-
-        Xn = casadi.horzcat(*Xn_variables)
-        U = casadi.horzcat(*U_variables)
-
-        # printme(number) is the debug.
-        Xk_begin = casadi.horzcat(self.X0, Xn)
-        Xk_end = self.next_X.map(self.N, "thread")(Xk_begin, U)
-        J = casadi.sum2(self.cost.map(self.N, "thread")(Xk_end, U, self.R))
-
-        # Put U and Xn interleaved into w to go fast.
-        for i in range(self.N):
-            self.w += [U_variables[i]]
-            self.ubw += [100] * 8
-            self.lbw += [-100] * 8
-
-            if i == self.N - 1:
-                continue
-
-            self.w += [Xn_variables[i]]
-            self.ubw += [casadi.inf] * dynamics.NUM_VELOCITY_STATES
-            self.lbw += [-casadi.inf] * dynamics.NUM_VELOCITY_STATES
-
-        self.g += [
-            casadi.reshape(Xn - Xk_end[:, 0:(self.N - 1)],
-                           dynamics.NUM_VELOCITY_STATES * (self.N - 1), 1)
-        ]
-
-        self.lbg += [0] * dynamics.NUM_VELOCITY_STATES * (self.N - 1)
-        self.ubg += [0] * dynamics.NUM_VELOCITY_STATES * (self.N - 1)
-
-        prob = {
-            'f': J,
-            # lbx <= x <= ubx
-            'x': casadi.vertcat(*self.w),
-            # lbg <= g(x, p) <= ubg
-            'g': casadi.vertcat(*self.g),
-            # Input parameters (initial position + goal)
-            'p': casadi.vertcat(self.X0, self.R),
-        }
-
-        compiler = "ccache clang"
-        flags = ["-O3"]
-        jit_options = {
-            "flags": flags,
-            "verbose": False,
-            "compiler": compiler,
-            "temp_suffix": False,
-        }
-
-        if solver == 'fatrop':
-            equality = [
-                True
-                for _ in range(dynamics.NUM_VELOCITY_STATES * (self.N - 1))
-            ]
-            options = {
-                "jit": True,
-                "jit_cleanup": False,
-                "jit_temp_suffix": False,
-                "compiler": "shell",
-                "jit_options": jit_options,
-                "structure_detection": "auto",
-                "fatrop": {
-                    "tol": 1e-7
-                },
-                "debug": True,
-                "equality": equality,
-            }
-        else:
-            options = {
-                "jit": True,
-                "jit_cleanup": False,
-                "jit_temp_suffix": False,
-                "compiler": "shell",
-                "jit_options": jit_options,
-            }
-            if full_debug:
-                options["jit"] = False
-                options["ipopt"] = {
-                    "print_level": 12,
-                }
-
-        self.solver = casadi.nlpsol('solver', solver, prob, options)
-
-    # TODO(austin): Vary the number of sub steps to be more short term and fewer long term?
-    def make_physics(self):
-        X0 = casadi.MX.sym('X0', dynamics.NUM_VELOCITY_STATES)
-        U = casadi.MX.sym('U', 8)
-
-        X = X0
-        M = 2  # RK4 steps per interval
-        DT = self.dt / M
-
-        for j in range(M):
-            k1 = self.velocity_fdot(X, U)
-            k2 = self.velocity_fdot(X + DT / 2 * k1, U)
-            k3 = self.velocity_fdot(X + DT / 2 * k2, U)
-            k4 = self.velocity_fdot(X + DT * k3, U)
-            X = X + DT / 6 * (k1 + 2 * k2 + 2 * k3 + k4)
-
-        return casadi.Function("next_X", [X0, U], [X])
-
-    def make_cost(self):
-        # TODO(austin): tune cost fn?
-        # Do we want to penalize slipping tires?
-        # Do we want to penalize powers unevenly applied across the motors?
-        # Need to do some simulations to see what works well.
-
-        X = casadi.MX.sym('X', dynamics.NUM_VELOCITY_STATES)
-        U = casadi.MX.sym('U', 8)
-        R = casadi.MX.sym('R', 3)
-
-        J = 0
-        vnorm = casadi.sqrt(R[0]**2.0 + R[1]**2.0)
-
-        vnormx = casadi.if_else(vnorm > 0.0001, R[0] / vnorm, 1.0)
-        vnormy = casadi.if_else(vnorm > 0.0001, R[1] / vnorm, 0.0)
-
-        vperpx = casadi.if_else(vnorm > 0.0001, -vnormy, 0.0)
-        vperpy = casadi.if_else(vnorm > 0.0001, vnormx, 1.0)
-
-        # TODO(austin): Do we want to do something more special for 0?
-
-        # cost velocity a lot more in the perpendicular direction to allow tire to spin up
-        # we also only want to get moving in the correct direction as fast as possible
-        J += 75 * ((R[0] - X[dynamics.VELOCITY_STATE_VX]) * vnormx +
-                   (R[1] - X[dynamics.VELOCITY_STATE_VY]) * vnormy)**2.0
-
-        J += 1500 * ((R[0] - X[dynamics.VELOCITY_STATE_VX]) * vperpx +
-                     (R[1] - X[dynamics.VELOCITY_STATE_VY]) * vperpy)**2.0
-
-        J += 1000 * (R[2] - X[dynamics.VELOCITY_STATE_OMEGA])**2.0
-
-        kSteerPositionGain = 0
-        kSteerVelocityGain = 0.10
-        J += kSteerPositionGain * (X[dynamics.VELOCITY_STATE_THETAS0])**2.0
-        J += kSteerVelocityGain * (X[dynamics.VELOCITY_STATE_OMEGAS0])**2.0
-
-        J += kSteerPositionGain * (X[dynamics.VELOCITY_STATE_THETAS1])**2.0
-        J += kSteerVelocityGain * (X[dynamics.VELOCITY_STATE_OMEGAS1])**2.0
-
-        J += kSteerPositionGain * (X[dynamics.VELOCITY_STATE_THETAS2])**2.0
-        J += kSteerVelocityGain * (X[dynamics.VELOCITY_STATE_OMEGAS2])**2.0
-
-        J += kSteerPositionGain * (X[dynamics.VELOCITY_STATE_THETAS3])**2.0
-        J += kSteerVelocityGain * (X[dynamics.VELOCITY_STATE_OMEGAS3])**2.0
-
-        # cost variance of the force by a tire and the expected average force and torque on it
-        total_force = self.force_vel[0](X, U)
-        total_torque = self.torque_cross(self.mounting_location[0](X, U),
-                                         self.force_vel[0](X, U))
-        for i in range(3):
-            total_force += self.force_vel[i + 1](X, U)
-            total_torque += self.torque_cross(
-                self.mounting_location[i + 1](X, U), self.force_vel[i + 1](X,
-                                                                           U))
-
-        total_force /= 4
-        total_torque /= 4
-        for i in range(4):
-            f_diff = (total_force +
-                      self.force_cross(total_torque, self.mounting_location[i]
-                                       (X, U))) - self.force_vel[i](X, U)
-            J += 0.01 * (f_diff[0, 0]**2.0 + f_diff[1, 0]**2.0)
-
-        # TODO(austin): Don't penalize torque steering current.
-        for i in range(4):
-            Is = U[2 * i + 0]
-            Id = U[2 * i + 1]
-            # Steer, cost it a lot less than drive to be more agressive in steering
-            J += ((Is + dynamics.STEER_CURRENT_COUPLING_FACTOR * Id)**
-                  2.0) / 100000.0
-            # Drive
-            J += Id * Id / 1000.0
-
-        return casadi.Function("Jn", [X, U, R], [J])
-
-    def torque_cross_func(self, r, F):
-        result = casadi.SX.sym('Tau', 1, 1)
-        result[0, 0] = r[0, 0] * F[1, 0] - r[1, 0] * F[0, 0]
-        return casadi.Function('Tau', [r, F], [result])
-
-    def force_cross_func(self, Tau, r):
-        result = casadi.SX.sym('F', 2, 1)
-        result[0, 0] = -r[1, 0] * Tau[0, 0] / casadi.norm_2(r)**2.0
-        result[1, 0] = r[0, 0] * Tau[0, 0] / casadi.norm_2(r)**2.0
-        return casadi.Function('F', [Tau, r], [result])
-
-    def solve(self, p, seed=None):
-        if seed is None:
-            seed = []
-
-            for i in range(self.N):
-                seed += [0, 0] * 4
-                if i < self.N - 1:
-                    seed += list(p[:dynamics.NUM_VELOCITY_STATES, 0])
-
-        return self.solver(x0=seed,
-                           lbx=self.lbw,
-                           ubx=self.ubw,
-                           lbg=self.lbg,
-                           ubg=self.ubg,
-                           p=casadi.DM(p))
-
-    def unpack_u(self, sol, i):
-        return sol['x'].full().flatten()[
-            (8 + dynamics.NUM_VELOCITY_STATES) *
-            i:((8 + dynamics.NUM_VELOCITY_STATES) * i + 8)]
-
-    def unpack_x(self, sol, i):
-        return sol['x'].full().flatten(
-        )[8 + (8 + dynamics.NUM_VELOCITY_STATES) *
-          (i - 1):(8 + dynamics.NUM_VELOCITY_STATES) * i]
-
 
 class Solver(object):
 
@@ -423,10 +133,12 @@
 
                 last_time = time.time()
 
-        print(f"Tool {overall_time} seconds overall to solve.")
+        print(f"Took {overall_time} seconds overall to solve.")
 
 
 def main(argv):
+    matplotlib.use("GTK3Agg")
+
     if FLAGS.outputdir:
         os.chdir(FLAGS.outputdir)
 
@@ -457,7 +169,7 @@
     R_goal[1, 0] = FLAGS.vy
     R_goal[2, 0] = FLAGS.omega
 
-    mpc = MPC(solver='fatrop') if not full_debug else MPC(solver='ipopt')
+    mpc = MPC(solver='fatrop') if not FLAGS.full_debug else MPC(solver='ipopt')
     solver = Solver()
     if not FLAGS.compileonly:
         results = solver.solve(mpc=mpc,
diff --git a/frc971/control_loops/swerve/casadi_velocity_mpc_lib.py b/frc971/control_loops/swerve/casadi_velocity_mpc_lib.py
new file mode 100644
index 0000000..e358422
--- /dev/null
+++ b/frc971/control_loops/swerve/casadi_velocity_mpc_lib.py
@@ -0,0 +1,288 @@
+#!/usr/bin/env python3
+
+from frc971.control_loops.swerve import dynamics
+import casadi
+import numpy
+from absl import flags
+
+FLAGS = flags.FLAGS
+
+# Full print level on ipopt. Piping to a file and using a filter or search method is suggested
+# grad_x prints out the gradient at each iteration in the following sequence: U0, X1, U1, etc.
+flags.DEFINE_bool('full_debug', False,
+                  'If true, turn on all the debugging in the solver.')
+
+
+class MPC(object):
+
+    def __init__(self, solver='fatrop', jit=True, N=200):
+        self.fdot = dynamics.swerve_full_dynamics(
+            casadi.SX.sym("X", dynamics.NUM_STATES, 1),
+            casadi.SX.sym("U", 8, 1))
+        self.velocity_fdot = dynamics.velocity_swerve_physics(
+            casadi.SX.sym("X", dynamics.NUM_VELOCITY_STATES, 1),
+            casadi.SX.sym("U", 8, 1))
+
+        self.wrapped_swerve_physics = lambda X, U: numpy.array(self.fdot(X, U))
+
+        self.dt = 0.005
+
+        # TODO(austin): Do we need a disturbance torque per module to account for friction?
+        # Do it only in the observer/post?
+
+        self.force = [
+            dynamics.F(i, casadi.SX.sym("X", 25, 1), casadi.SX.sym("U", 8, 1))
+            for i in range(4)
+        ]
+        self.force_vel = [
+            dynamics.F_vel(i,
+                           casadi.SX.sym("X", dynamics.NUM_VELOCITY_STATES, 1),
+                           casadi.SX.sym("U", 8, 1)) for i in range(4)
+        ]
+        self.slip_angle = [
+            dynamics.slip_angle(i, casadi.SX.sym("X", 25, 1),
+                                casadi.SX.sym("U", 8, 1)) for i in range(4)
+        ]
+        self.rotated_mounting_location = [
+            dynamics.rotated_mounting_location(
+                i, casadi.SX.sym("X", dynamics.NUM_VELOCITY_STATES, 1),
+                casadi.SX.sym("U", 8, 1)) for i in range(4)
+        ]
+        self.torque_cross = self.torque_cross_func(casadi.SX.sym("r", 2, 1),
+                                                   casadi.SX.sym("F", 2, 1))
+        self.force_cross = self.force_cross_func(casadi.SX.sym("Tau", 1, 1),
+                                                 casadi.SX.sym("r", 2, 1))
+        self.next_X = self.make_physics()
+        self.cost = self.make_cost()
+
+        self.N = N
+
+        # Start with an empty nonlinear program.
+        self.w = []
+        self.lbw = []
+        self.ubw = []
+        J = 0
+        self.g = []
+        self.lbg = []
+        self.ubg = []
+
+        self.X0 = casadi.MX.sym('X0', dynamics.NUM_VELOCITY_STATES)
+
+        # We care about the linear and angular velocities only.
+        self.R = casadi.MX.sym('R', 3)
+
+        # Make Xn and U for each step.  fatrop wants us to interleave the control variables and
+        # states so that it can produce a banded/structured problem which it can solve a lot
+        # faster.
+        Xn_variables = []
+        U_variables = []
+        for i in range(self.N):
+            U_variables.append(casadi.MX.sym(f'U{i}', 8))
+
+            if i == 0:
+                continue
+
+            Xn_variables.append(
+                casadi.MX.sym(f'X{i}', dynamics.NUM_VELOCITY_STATES))
+
+        Xn = casadi.horzcat(*Xn_variables)
+        U = casadi.horzcat(*U_variables)
+
+        # printme(number) is the debug.
+        Xk_begin = casadi.horzcat(self.X0, Xn)
+        Xk_end = self.next_X.map(self.N, "thread")(Xk_begin, U)
+        J = casadi.sum2(self.cost.map(self.N, "thread")(Xk_end, U, self.R))
+
+        # Put U and Xn interleaved into w to go fast.
+        for i in range(self.N):
+            self.w += [U_variables[i]]
+            self.ubw += [100] * 8
+            self.lbw += [-100] * 8
+
+            if i == self.N - 1:
+                continue
+
+            self.w += [Xn_variables[i]]
+            self.ubw += [casadi.inf] * dynamics.NUM_VELOCITY_STATES
+            self.lbw += [-casadi.inf] * dynamics.NUM_VELOCITY_STATES
+
+        self.g += [
+            casadi.reshape(Xn - Xk_end[:, 0:(self.N - 1)],
+                           dynamics.NUM_VELOCITY_STATES * (self.N - 1), 1)
+        ]
+
+        self.lbg += [0] * dynamics.NUM_VELOCITY_STATES * (self.N - 1)
+        self.ubg += [0] * dynamics.NUM_VELOCITY_STATES * (self.N - 1)
+
+        prob = {
+            'f': J,
+            # lbx <= x <= ubx
+            'x': casadi.vertcat(*self.w),
+            # lbg <= g(x, p) <= ubg
+            'g': casadi.vertcat(*self.g),
+            # Input parameters (initial position + goal)
+            'p': casadi.vertcat(self.X0, self.R),
+        }
+
+        compiler = "ccache clang"
+        flags = ["-O3"]
+        jit_options = {
+            "flags": flags,
+            "verbose": True,
+            "compiler": compiler,
+            "temp_suffix": False,
+        }
+
+        if solver == 'fatrop':
+            equality = [
+                True
+                for _ in range(dynamics.NUM_VELOCITY_STATES * (self.N - 1))
+            ]
+            options = {
+                "jit": jit,
+                "jit_cleanup": False,
+                "jit_temp_suffix": False,
+                "compiler": "shell",
+                "jit_options": jit_options,
+                "structure_detection": "auto",
+                "fatrop": {
+                    "tol": 1e-7
+                },
+                "debug": True,
+                "equality": equality,
+            }
+        else:
+            options = {
+                "jit": jit,
+                "jit_cleanup": False,
+                "jit_temp_suffix": False,
+                "compiler": "shell",
+                "jit_options": jit_options,
+            }
+            if FLAGS.full_debug:
+                options["jit"] = False
+                options["ipopt"] = {
+                    "print_level": 12,
+                }
+
+        self.solver = casadi.nlpsol('solver', solver, prob, options)
+
+    # TODO(austin): Vary the number of sub steps to be more short term and fewer long term?
+    def make_physics(self):
+        X0 = casadi.MX.sym('X0', dynamics.NUM_VELOCITY_STATES)
+        U = casadi.MX.sym('U', 8)
+
+        X = X0
+        M = 2  # RK4 steps per interval
+        DT = self.dt / M
+
+        for j in range(M):
+            k1 = self.velocity_fdot(X, U)
+            k2 = self.velocity_fdot(X + DT / 2 * k1, U)
+            k3 = self.velocity_fdot(X + DT / 2 * k2, U)
+            k4 = self.velocity_fdot(X + DT * k3, U)
+            X = X + DT / 6 * (k1 + 2 * k2 + 2 * k3 + k4)
+
+        return casadi.Function("next_X", [X0, U], [X])
+
+    def make_cost(self):
+        # TODO(austin): tune cost fn?
+        # Need to do some simulations to see what works well.
+
+        X = casadi.MX.sym('X', dynamics.NUM_VELOCITY_STATES)
+        U = casadi.MX.sym('U', 8)
+        R = casadi.MX.sym('R', 3)
+
+        J = 0
+        vnorm = casadi.sqrt(R[0]**2.0 + R[1]**2.0)
+
+        vnormx = casadi.if_else(vnorm > 0.0001, R[0] / vnorm, 1.0)
+        vnormy = casadi.if_else(vnorm > 0.0001, R[1] / vnorm, 0.0)
+
+        vperpx = casadi.if_else(vnorm > 0.0001, -vnormy, 0.0)
+        vperpy = casadi.if_else(vnorm > 0.0001, vnormx, 1.0)
+
+        # TODO(austin): Do we want to do something more special for 0?
+
+        # cost velocity a lot more in the perpendicular direction to allow tire to spin up
+        # we also only want to get moving in the correct direction as fast as possible
+        J += 75 * ((R[0] - X[dynamics.VELOCITY_STATE_VX]) * vnormx +
+                   (R[1] - X[dynamics.VELOCITY_STATE_VY]) * vnormy)**2.0
+
+        J += 1500 * ((R[0] - X[dynamics.VELOCITY_STATE_VX]) * vperpx +
+                     (R[1] - X[dynamics.VELOCITY_STATE_VY]) * vperpy)**2.0
+
+        J += 1000 * (R[2] - X[dynamics.VELOCITY_STATE_OMEGA])**2.0
+
+        kSteerVelocityGain = 0.10
+        J += kSteerVelocityGain * (X[dynamics.VELOCITY_STATE_OMEGAS0])**2.0
+        J += kSteerVelocityGain * (X[dynamics.VELOCITY_STATE_OMEGAS1])**2.0
+        J += kSteerVelocityGain * (X[dynamics.VELOCITY_STATE_OMEGAS2])**2.0
+        J += kSteerVelocityGain * (X[dynamics.VELOCITY_STATE_OMEGAS3])**2.0
+
+        # cost variance of the force by a tire and the expected average force and torque on it
+        total_force = self.force_vel[0](X, U)
+        total_torque = self.torque_cross(
+            self.rotated_mounting_location[0](X, U), self.force_vel[0](X, U))
+        for i in range(3):
+            total_force += self.force_vel[i + 1](X, U)
+            total_torque += self.torque_cross(
+                self.rotated_mounting_location[i + 1](X, U),
+                self.force_vel[i + 1](X, U))
+
+        total_force /= 4
+        total_torque /= 4
+        for i in range(4):
+            f_diff = (total_force + self.force_cross(
+                total_torque, self.rotated_mounting_location[i]
+                (X, U))) - self.force_vel[i](X, U)
+            J += 0.01 * (f_diff[0, 0]**2.0 + f_diff[1, 0]**2.0)
+
+        # TODO(austin): Don't penalize torque steering current.
+        for i in range(4):
+            Is = U[2 * i + 0]
+            Id = U[2 * i + 1]
+            # Steer, cost it a lot less than drive to be more agressive in steering
+            J += ((Is + dynamics.STEER_CURRENT_COUPLING_FACTOR * Id)**
+                  2.0) / 100000.0
+            # Drive
+            J += Id * Id / 1000.0
+
+        return casadi.Function("Jn", [X, U, R], [J])
+
+    def torque_cross_func(self, r, F):
+        result = casadi.SX.sym('Tau', 1, 1)
+        result[0, 0] = r[0, 0] * F[1, 0] - r[1, 0] * F[0, 0]
+        return casadi.Function('Tau', [r, F], [result])
+
+    def force_cross_func(self, Tau, r):
+        result = casadi.SX.sym('F', 2, 1)
+        result[0, 0] = -r[1, 0] * Tau[0, 0] / casadi.norm_2(r)**2.0
+        result[1, 0] = r[0, 0] * Tau[0, 0] / casadi.norm_2(r)**2.0
+        return casadi.Function('F', [Tau, r], [result])
+
+    def solve(self, p, seed=None):
+        if seed is None:
+            seed = []
+
+            for i in range(self.N):
+                seed += [0, 0] * 4
+                if i < self.N - 1:
+                    seed += list(p[:dynamics.NUM_VELOCITY_STATES, 0])
+
+        return self.solver(x0=seed,
+                           lbx=self.lbw,
+                           ubx=self.ubw,
+                           lbg=self.lbg,
+                           ubg=self.ubg,
+                           p=casadi.DM(p))
+
+    def unpack_u(self, sol, i):
+        return sol['x'].full().flatten()[
+            (8 + dynamics.NUM_VELOCITY_STATES) *
+            i:((8 + dynamics.NUM_VELOCITY_STATES) * i + 8)]
+
+    def unpack_x(self, sol, i):
+        return sol['x'].full().flatten(
+        )[8 + (8 + dynamics.NUM_VELOCITY_STATES) *
+          (i - 1):(8 + dynamics.NUM_VELOCITY_STATES) * i]
diff --git a/frc971/control_loops/swerve/experience_collector.py b/frc971/control_loops/swerve/experience_collector.py
new file mode 100644
index 0000000..b4c17fb
--- /dev/null
+++ b/frc971/control_loops/swerve/experience_collector.py
@@ -0,0 +1,201 @@
+#!/usr/bin/env python3
+import os, sys
+
+# Setup XLA first.
+os.environ['XLA_FLAGS'] = ' '.join([
+    # Teach it where to find CUDA
+    '--xla_gpu_cuda_data_dir=/usr/lib/cuda',
+    # Use up to 20 cores
+    #'--xla_force_host_platform_device_count=6',
+    # Dump XLA to /tmp/foo to aid debugging
+    #'--xla_dump_to=/tmp/foo',
+    #'--xla_gpu_enable_command_buffer='
+    # Dump sharding
+    #"--xla_dump_to=/tmp/foo",
+    #"--xla_dump_hlo_pass_re=spmd|propagation"
+])
+os.environ['JAX_PLATFORMS'] = 'cpu'
+os.environ['XLA_PYTHON_CLIENT_PREALLOCATE'] = 'false'
+os.environ['XLA_PYTHON_CLIENT_MEM_FRACTION'] = '.50'
+
+from absl import flags
+from absl import app
+from absl import logging
+import pickle
+import numpy
+from frc971.control_loops.swerve import dynamics
+from frc971.control_loops.swerve.casadi_velocity_mpc_lib import MPC
+import jax
+import tensorflow as tf
+from frc971.control_loops.swerve.velocity_controller.physics import SwerveProblem
+from frc971.control_loops.swerve import jax_dynamics
+
+FLAGS = flags.FLAGS
+
+flags.DEFINE_bool('compileonly', False,
+                  'If true, load casadi, don\'t compile it')
+
+flags.DEFINE_float('vx', 1.0, 'Goal velocity in m/s in x')
+flags.DEFINE_float('vy', 0.0, 'Goal velocity in m/s in y')
+flags.DEFINE_float('omega', 0.0, 'Goal velocity in m/s in omega')
+flags.DEFINE_integer('seed', 0, 'Seed for random initial state.')
+
+flags.DEFINE_bool('save_plots', True,
+                  'If true, save plots for each run as well.')
+flags.DEFINE_string('outputdir', None, 'Directory to write problem results to')
+flags.DEFINE_bool('quiet', False, 'If true, print a lot less')
+
+flags.DEFINE_integer('num_solutions', 100,
+                     'Number of random problems to solve.')
+flags.DEFINE_integer('horizon', 200, 'Horizon to solve for')
+
+try:
+    from matplotlib import pylab
+except ModuleNotFoundError:
+    pass
+
+
+def collect_experience(problem, mpc, rng):
+    X_initial = numpy.array(problem.random_states(rng,
+                                                  dimensions=1)).transpose()
+
+    R_goal = numpy.zeros((3, 1))
+    R_goal[0, 0] = FLAGS.vx
+    R_goal[1, 0] = FLAGS.vy
+    R_goal[2, 0] = FLAGS.omega
+
+    solution = mpc.solve(p=numpy.vstack((X_initial, R_goal)))
+    sys.stderr.flush()
+    sys.stdout.flush()
+
+    # Solver doesn't solve for the last state.  So we get N-1 states back.
+    experience = {
+        'observations1': numpy.zeros((mpc.N - 1, problem.num_states)),
+        'observations2': numpy.zeros((mpc.N - 1, problem.num_states)),
+        'actions': numpy.zeros((mpc.N - 1, problem.num_outputs)),
+        'rewards': numpy.zeros((mpc.N - 1, 1)),
+        'goals': numpy.zeros((mpc.N - 1, problem.num_goals)),
+    }
+
+    if not FLAGS.quiet:
+        print('x(0):', X_initial.transpose())
+
+    logging.info('Finished solving')
+    X_prior = X_initial.squeeze()
+    for j in range(mpc.N - 1):
+        if not FLAGS.quiet:
+            print(f'u({j}): ', mpc.unpack_u(solution, j))
+            print(f'x({j+1}): ', mpc.unpack_x(solution, j + 1))
+        experience['observations1'][j, :] = X_prior
+        X_prior = mpc.unpack_x(solution, j + 1)
+        experience['observations2'][j, :] = X_prior
+        experience['actions'][j, :] = mpc.unpack_u(solution, j)
+        experience['goals'][j, :] = R_goal[:, 0]
+
+    logging.info('Finished all but reward')
+    for j in range(mpc.N - 1):
+        experience['rewards'][j, :] = problem.reward(
+            X=X_prior,
+            U=mpc.unpack_u(solution, j),
+            goal=R_goal[:, 0],
+        )
+    sys.stderr.flush()
+    sys.stdout.flush()
+
+    return experience
+
+
+def save_experience(problem, mpc, experience, experience_number):
+    with open(f'experience_{experience_number}.pkl', 'wb') as f:
+        pickle.dump(experience, f)
+
+    if not FLAGS.save_plots:
+        return
+
+    fig0, axs0 = pylab.subplots(3)
+    fig1, axs1 = pylab.subplots(2)
+
+    axs0[0].clear()
+    axs0[1].clear()
+    axs0[2].clear()
+
+    t = problem.dt * numpy.array(list(range(mpc.N - 1)))
+
+    X_plot = experience['observations1']
+    U_plot = experience['actions']
+
+    axs0[0].plot(t, X_plot[:, dynamics.VELOCITY_STATE_VX], label="vx")
+    axs0[0].plot(t, X_plot[:, dynamics.VELOCITY_STATE_VY], label="vy")
+    axs0[0].plot(t, X_plot[:, dynamics.VELOCITY_STATE_OMEGA], label="omega")
+    axs0[0].legend()
+
+    axs0[1].plot(t, U_plot[:, 0], label="Is0")
+    axs0[1].plot(t, U_plot[:, 2], label="Is1")
+    axs0[1].plot(t, U_plot[:, 4], label="Is2")
+    axs0[1].plot(t, U_plot[:, 6], label="Is3")
+    axs0[1].legend()
+
+    axs0[2].plot(t, U_plot[:, 1], label="Id0")
+    axs0[2].plot(t, U_plot[:, 3], label="Id1")
+    axs0[2].plot(t, U_plot[:, 5], label="Id2")
+    axs0[2].plot(t, U_plot[:, 7], label="Id3")
+    axs0[2].legend()
+
+    axs1[0].clear()
+    axs1[1].clear()
+
+    axs1[0].plot(t, X_plot[:, dynamics.VELOCITY_STATE_THETAS0], label='steer0')
+    axs1[0].plot(t, X_plot[:, dynamics.VELOCITY_STATE_THETAS1], label='steer1')
+    axs1[0].plot(t, X_plot[:, dynamics.VELOCITY_STATE_THETAS2], label='steer2')
+    axs1[0].plot(t, X_plot[:, dynamics.VELOCITY_STATE_THETAS3], label='steer3')
+    axs1[0].legend()
+    axs1[1].plot(t,
+                 X_plot[:, dynamics.VELOCITY_STATE_OMEGAS0],
+                 label='steer_velocity0')
+    axs1[1].plot(t,
+                 X_plot[:, dynamics.VELOCITY_STATE_OMEGAS1],
+                 label='steer_velocity1')
+    axs1[1].plot(t,
+                 X_plot[:, dynamics.VELOCITY_STATE_OMEGAS2],
+                 label='steer_velocity2')
+    axs1[1].plot(t,
+                 X_plot[:, dynamics.VELOCITY_STATE_OMEGAS3],
+                 label='steer_velocity3')
+    axs1[1].legend()
+
+    fig0.savefig(f'state_{experience_number}.svg')
+    fig1.savefig(f'steer_{experience_number}.svg')
+
+    # Free the memory associated with the figures.
+    fig0.clf()
+    fig1.clf()
+    pylab.close(fig0)
+    pylab.close(fig1)
+
+
+def main(argv):
+    if FLAGS.outputdir:
+        os.chdir(FLAGS.outputdir)
+
+    # Hide any GPUs from TensorFlow. Otherwise it might reserve memory.
+    tf.config.experimental.set_visible_devices([], 'GPU')
+    rng = jax.random.key(FLAGS.seed)
+
+    physics_constants = jax_dynamics.Coefficients()
+    problem = SwerveProblem(physics_constants)
+    mpc = MPC(solver='ipopt', N=(FLAGS.horizon + 1))
+
+    if FLAGS.compileonly:
+        return
+
+    for i in range(FLAGS.num_solutions):
+        rng, rng_init = jax.random.split(rng)
+        experience = collect_experience(problem, mpc, rng_init)
+        logging.info('Solved problem %d', i)
+
+        save_experience(problem, mpc, experience, i)
+        logging.info('Wrote problem %d', i)
+
+
+if __name__ == '__main__':
+    app.run(main)
diff --git a/frc971/control_loops/swerve/generate_physics.cc b/frc971/control_loops/swerve/generate_physics.cc
index af058f6..de52d79 100644
--- a/frc971/control_loops/swerve/generate_physics.cc
+++ b/frc971/control_loops/swerve/generate_physics.cc
@@ -32,6 +32,8 @@
           "Path to write generated header code to");
 ABSL_FLAG(std::string, casadi_py_output_path, "",
           "Path to write casadi generated py code to");
+ABSL_FLAG(std::string, constants_output_path, "",
+          "Path to write constants python code to");
 ABSL_FLAG(double, caster, 0.01, "Caster in meters for the module.");
 
 ABSL_FLAG(bool, symbolic, false, "If true, write everything out symbolically.");
@@ -68,6 +70,7 @@
 // State per module.
 struct Module {
   DenseMatrix mounting_location;
+  DenseMatrix rotated_mounting_location;
 
   RCP<const Symbol> Is;
 
@@ -625,6 +628,80 @@
     }
   }
 
+  void WriteConstantsFile(std::string_view path) {
+    std::vector<std::string> result_py;
+
+    // Write out the header.
+    result_py.emplace_back("#!/usr/bin/env python3");
+    result_py.emplace_back("");
+
+    WriteConstants(&result_py);
+
+    aos::util::WriteStringToFileOrDie(path, absl::StrJoin(result_py, "\n"));
+  }
+
+  void WriteConstants(std::vector<std::string> *result_py) {
+    result_py->emplace_back(absl::Substitute("WHEEL_RADIUS = $0", ccode(*rw_)));
+    result_py->emplace_back(
+        absl::Substitute("ROBOT_WIDTH = $0", ccode(*robot_width_)));
+    result_py->emplace_back(absl::Substitute("CASTER = $0", ccode(*caster_)));
+    result_py->emplace_back("STATE_THETAS0 = 0");
+    result_py->emplace_back("STATE_THETAD0 = 1");
+    result_py->emplace_back("STATE_OMEGAS0 = 2");
+    result_py->emplace_back("STATE_OMEGAD0 = 3");
+    result_py->emplace_back("STATE_THETAS1 = 4");
+    result_py->emplace_back("STATE_THETAD1 = 5");
+    result_py->emplace_back("STATE_OMEGAS1 = 6");
+    result_py->emplace_back("STATE_OMEGAD1 = 7");
+    result_py->emplace_back("STATE_THETAS2 = 8");
+    result_py->emplace_back("STATE_THETAD2 = 9");
+    result_py->emplace_back("STATE_OMEGAS2 = 10");
+    result_py->emplace_back("STATE_OMEGAD2 = 11");
+    result_py->emplace_back("STATE_THETAS3 = 12");
+    result_py->emplace_back("STATE_THETAD3 = 13");
+    result_py->emplace_back("STATE_OMEGAS3 = 14");
+    result_py->emplace_back("STATE_OMEGAD3 = 15");
+    result_py->emplace_back("STATE_X = 16");
+    result_py->emplace_back("STATE_Y = 17");
+    result_py->emplace_back("STATE_THETA = 18");
+    result_py->emplace_back("STATE_VX = 19");
+    result_py->emplace_back("STATE_VY = 20");
+    result_py->emplace_back("STATE_OMEGA = 21");
+    result_py->emplace_back("STATE_FX = 22");
+    result_py->emplace_back("STATE_FY = 23");
+    result_py->emplace_back("STATE_MOMENT = 24");
+    result_py->emplace_back("NUM_STATES = 25");
+    result_py->emplace_back("");
+    result_py->emplace_back("VELOCITY_STATE_THETAS0 = 0");
+    result_py->emplace_back("VELOCITY_STATE_OMEGAS0 = 1");
+    result_py->emplace_back("VELOCITY_STATE_THETAS1 = 2");
+    result_py->emplace_back("VELOCITY_STATE_OMEGAS1 = 3");
+    result_py->emplace_back("VELOCITY_STATE_THETAS2 = 4");
+    result_py->emplace_back("VELOCITY_STATE_OMEGAS2 = 5");
+    result_py->emplace_back("VELOCITY_STATE_THETAS3 = 6");
+    result_py->emplace_back("VELOCITY_STATE_OMEGAS3 = 7");
+    result_py->emplace_back("VELOCITY_STATE_THETA = 8");
+    result_py->emplace_back("VELOCITY_STATE_VX = 9");
+    result_py->emplace_back("VELOCITY_STATE_VY = 10");
+    result_py->emplace_back("VELOCITY_STATE_OMEGA = 11");
+    // result_py->emplace_back("VELOCITY_STATE_FX = 16");
+    // result_py->emplace_back("VELOCITY_STATE_FY = 17");
+    // result_py->emplace_back("VELOCITY_STATE_MOMENT = 18");
+    result_py->emplace_back("NUM_VELOCITY_STATES = 12");
+    result_py->emplace_back("");
+    result_py->emplace_back("");
+    result_py->emplace_back("# Is = STEER_CURRENT_COUPLING_FACTOR * Id");
+    result_py->emplace_back(absl::Substitute(
+        "STEER_CURRENT_COUPLING_FACTOR = $0",
+        ccode(*(neg(
+            mul(div(Gs_, Kts_),
+                mul(div(Ktd_, mul(Gd_, rw_)),
+                    neg(mul(add(neg(wb_), mul(add(rs_, rp_),
+                                              sub(integer(1), div(rb1_, rp_)))),
+                            div(rw_, rb2_))))))))));
+    result_py->emplace_back("");
+  }
+
   // Writes the physics out to the provided .cc and .h path.
   void WriteCasadi(std::string_view py_path) {
     std::vector<std::string> result_py;
@@ -634,54 +711,9 @@
     result_py.emplace_back("");
     result_py.emplace_back("import casadi, numpy");
     result_py.emplace_back("");
-    result_py.emplace_back(absl::Substitute("WHEEL_RADIUS = $0", ccode(*rw_)));
-    result_py.emplace_back(
-        absl::Substitute("ROBOT_WIDTH = $0", ccode(*robot_width_)));
-    result_py.emplace_back(absl::Substitute("CASTER = $0", ccode(*caster_)));
-    result_py.emplace_back("STATE_THETAS0 = 0");
-    result_py.emplace_back("STATE_THETAD0 = 1");
-    result_py.emplace_back("STATE_OMEGAS0 = 2");
-    result_py.emplace_back("STATE_OMEGAD0 = 3");
-    result_py.emplace_back("STATE_THETAS1 = 4");
-    result_py.emplace_back("STATE_THETAD1 = 5");
-    result_py.emplace_back("STATE_OMEGAS1 = 6");
-    result_py.emplace_back("STATE_OMEGAD1 = 7");
-    result_py.emplace_back("STATE_THETAS2 = 8");
-    result_py.emplace_back("STATE_THETAD2 = 9");
-    result_py.emplace_back("STATE_OMEGAS2 = 10");
-    result_py.emplace_back("STATE_OMEGAD2 = 11");
-    result_py.emplace_back("STATE_THETAS3 = 12");
-    result_py.emplace_back("STATE_THETAD3 = 13");
-    result_py.emplace_back("STATE_OMEGAS3 = 14");
-    result_py.emplace_back("STATE_OMEGAD3 = 15");
-    result_py.emplace_back("STATE_X = 16");
-    result_py.emplace_back("STATE_Y = 17");
-    result_py.emplace_back("STATE_THETA = 18");
-    result_py.emplace_back("STATE_VX = 19");
-    result_py.emplace_back("STATE_VY = 20");
-    result_py.emplace_back("STATE_OMEGA = 21");
-    result_py.emplace_back("STATE_FX = 22");
-    result_py.emplace_back("STATE_FY = 23");
-    result_py.emplace_back("STATE_MOMENT = 24");
-    result_py.emplace_back("NUM_STATES = 25");
-    result_py.emplace_back("");
-    result_py.emplace_back("VELOCITY_STATE_THETAS0 = 0");
-    result_py.emplace_back("VELOCITY_STATE_OMEGAS0 = 1");
-    result_py.emplace_back("VELOCITY_STATE_THETAS1 = 2");
-    result_py.emplace_back("VELOCITY_STATE_OMEGAS1 = 3");
-    result_py.emplace_back("VELOCITY_STATE_THETAS2 = 4");
-    result_py.emplace_back("VELOCITY_STATE_OMEGAS2 = 5");
-    result_py.emplace_back("VELOCITY_STATE_THETAS3 = 6");
-    result_py.emplace_back("VELOCITY_STATE_OMEGAS3 = 7");
-    result_py.emplace_back("VELOCITY_STATE_THETA = 8");
-    result_py.emplace_back("VELOCITY_STATE_VX = 9");
-    result_py.emplace_back("VELOCITY_STATE_VY = 10");
-    result_py.emplace_back("VELOCITY_STATE_OMEGA = 11");
-    // result_py.emplace_back("VELOCITY_STATE_FX = 16");
-    // result_py.emplace_back("VELOCITY_STATE_FY = 17");
-    // result_py.emplace_back("VELOCITY_STATE_MOMENT = 18");
-    result_py.emplace_back("NUM_VELOCITY_STATES = 12");
-    result_py.emplace_back("");
+
+    WriteConstants(&result_py);
+
     result_py.emplace_back("def to_velocity_state(X):");
     result_py.emplace_back("    return numpy.array([");
     result_py.emplace_back("        [X[STATE_THETAS0, 0]],");
@@ -732,27 +764,6 @@
                            "casadi.exp($1.0 * x))) * $0.0]))) / $0.0)",
                            kLogGain, kAbsGain));
     }
-    result_py.emplace_back("");
-    result_py.emplace_back("# Is = STEER_CURRENT_COUPLING_FACTOR * Id");
-    result_py.emplace_back(absl::Substitute(
-        "STEER_CURRENT_COUPLING_FACTOR = $0",
-        ccode(*(neg(
-            mul(div(Gs_, Kts_),
-                mul(div(Ktd_, mul(Gd_, rw_)),
-                    neg(mul(add(neg(wb_), mul(add(rs_, rp_),
-                                              sub(integer(1), div(rb1_, rp_)))),
-                            div(rw_, rb2_))))))))));
-    result_py.emplace_back("");
-    result_py.emplace_back("# Is = STEER_CURRENT_COUPLING_FACTOR * Id");
-    result_py.emplace_back(absl::Substitute(
-        "STEER_CURRENT_COUPLING_FACTOR = $0",
-        ccode(*(neg(
-            mul(div(Gs_, Kts_),
-                mul(div(Ktd_, mul(Gd_, rw_)),
-                    neg(mul(add(neg(wb_), mul(add(rs_, rp_),
-                                              sub(integer(1), div(rb1_, rp_)))),
-                            div(rw_, rb2_))))))))));
-    result_py.emplace_back("");
 
     result_py.emplace_back("# Returns the derivative of our state vector");
     result_py.emplace_back("# [thetas0, thetad0, omegas0, omegad0,");
@@ -928,6 +939,14 @@
         },
         &result_py);
 
+    DefineVector2dVelocityFunction(
+        "rotated_mounting_location",
+        "Returns the mounting location of wheel in field aligned coordinates",
+        [](const Module &m, int dimension) {
+          return ccode(*m.rotated_mounting_location.get(dimension, 0));
+        },
+        &result_py);
+
     DefineScalarFunction(
         "Ms", "Returns the self aligning moment of the ith wheel",
         [this](const Module &m) {
@@ -1179,17 +1198,18 @@
                     DenseMatrix(2, 1, {result.full.Fwx, result.Fwy}),
                     result.full.F);
 
-    DenseMatrix rotated_mounting_location = DenseMatrix(2, 1);
+    result.rotated_mounting_location = DenseMatrix(2, 1);
     mul_dense_dense(R(theta_), result.mounting_location,
-                    rotated_mounting_location);
-    result.full.torque = force_cross(rotated_mounting_location, result.full.F);
+                    result.rotated_mounting_location);
+    result.full.torque =
+        force_cross(result.rotated_mounting_location, result.full.F);
 
     result.direct.F = DenseMatrix(2, 1);
     mul_dense_dense(R(add(theta_, result.thetas)),
                     DenseMatrix(2, 1, {result.direct.Fwx, result.Fwy}),
                     result.direct.F);
     result.direct.torque =
-        force_cross(rotated_mounting_location, result.direct.F);
+        force_cross(result.rotated_mounting_location, result.direct.F);
 
     VLOG(1);
     VLOG(1) << "full torque = " << result.full.torque->__str__();
@@ -1284,5 +1304,9 @@
     sim.WriteCasadi(absl::GetFlag(FLAGS_casadi_py_output_path));
   }
 
+  if (!absl::GetFlag(FLAGS_constants_output_path).empty()) {
+    sim.WriteConstantsFile(absl::GetFlag(FLAGS_constants_output_path));
+  }
+
   return 0;
 }
diff --git a/frc971/control_loops/swerve/jax_dynamics.py b/frc971/control_loops/swerve/jax_dynamics.py
index dfadbda..58d5fcf 100644
--- a/frc971/control_loops/swerve/jax_dynamics.py
+++ b/frc971/control_loops/swerve/jax_dynamics.py
@@ -4,8 +4,8 @@
 from collections import namedtuple
 import jax
 
-from frc971.control_loops.swerve import dynamics
 from frc971.control_loops.python.control_loop import KrakenFOC
+from frc971.control_loops.swerve.dynamics_constants import *
 
 # Note: this physics needs to match the symengine code.  We have tests that
 # confirm they match in all the cases we care about.
@@ -130,36 +130,35 @@
             jax.numpy.array([1.0, softabs_x * kMaxLogGain])) / kMaxLogGain)
 
 
-def full_module_physics(coefficients: dict, Rtheta, module_index: int,
-                        mounting_location, X, U):
+def full_module_physics(coefficients: CoefficientsType, Rtheta,
+                        module_index: int, mounting_location, X, U):
     X_module = X[module_index * 4:(module_index + 1) * 4]
     Is = U[2 * module_index + 0]
     Id = U[2 * module_index + 1]
 
-    Rthetaplusthetas = R(X[dynamics.STATE_THETA] +
-                         X_module[dynamics.STATE_THETAS0])
+    Rthetaplusthetas = R(X[STATE_THETA] + X_module[STATE_THETAS0])
 
     caster_vector = jax.numpy.array([-coefficients.caster, 0.0])
 
-    robot_velocity = X[dynamics.STATE_VX:dynamics.STATE_VY + 1]
+    robot_velocity = X[STATE_VX:STATE_VY + 1]
 
     contact_patch_velocity = (
-        angle_cross(Rtheta @ mounting_location, X[dynamics.STATE_OMEGA]) +
-        robot_velocity + angle_cross(
-            Rthetaplusthetas @ caster_vector,
-            (X[dynamics.STATE_OMEGA] + X_module[dynamics.STATE_OMEGAS0])))
+        angle_cross(Rtheta @ mounting_location, X[STATE_OMEGA]) +
+        robot_velocity +
+        angle_cross(Rthetaplusthetas @ caster_vector,
+                    (X[STATE_OMEGA] + X_module[STATE_OMEGAS0])))
 
     wheel_ground_velocity = Rthetaplusthetas.T @ contact_patch_velocity
 
     wheel_velocity = jax.numpy.array(
-        [coefficients.rw * X_module[dynamics.STATE_OMEGAD0], 0.0])
+        [coefficients.rw * X_module[STATE_OMEGAD0], 0.0])
 
     wheel_slip_velocity = wheel_velocity - wheel_ground_velocity
 
     slip_angle = jax.numpy.sin(
         -soft_atan2(wheel_ground_velocity[1], wheel_ground_velocity[0]))
 
-    slip_ratio = (coefficients.rw * X_module[dynamics.STATE_OMEGAD0] -
+    slip_ratio = (coefficients.rw * X_module[STATE_OMEGAD0] -
                   wheel_ground_velocity[0]) / jax.numpy.max(
                       jax.numpy.array(
                           [0.02, jax.numpy.abs(wheel_ground_velocity[0])]))
@@ -193,8 +192,8 @@
 
     X_dot_contribution = jax.numpy.hstack((jax.numpy.zeros(
         (4, )), ) * (module_index) + (jax.numpy.array([
-            X_module[dynamics.STATE_OMEGAS0],
-            X_module[dynamics.STATE_OMEGAD0],
+            X_module[STATE_OMEGAS0],
+            X_module[STATE_OMEGAD0],
             alphas,
             alphad,
         ]), ) + (jax.numpy.zeros((4, )), ) * (3 - module_index) + (
@@ -208,7 +207,7 @@
 
 @partial(jax.jit, static_argnames=['coefficients'])
 def full_dynamics(coefficients: CoefficientsType, X, U):
-    Rtheta = R(X[dynamics.STATE_THETA])
+    Rtheta = R(X[STATE_THETA])
 
     module0 = full_module_physics(
         coefficients, Rtheta, 0,
@@ -233,37 +232,41 @@
 
     X_dot = module0 + module1 + module2 + module3
 
-    X_dot = X_dot.at[dynamics.STATE_X:dynamics.STATE_THETA + 1].set(
+    X_dot = X_dot.at[STATE_X:STATE_THETA + 1].set(
         jax.numpy.array([
-            X[dynamics.STATE_VX],
-            X[dynamics.STATE_VY],
-            X[dynamics.STATE_OMEGA],
+            X[STATE_VX],
+            X[STATE_VY],
+            X[STATE_OMEGA],
         ]))
 
     return X_dot
 
 
-def velocity_module_physics(coefficients: dict, Rtheta, module_index: int,
-                            mounting_location, X, U):
+def velocity_module_physics(coefficients: CoefficientsType,
+                            Rtheta: jax.typing.ArrayLike, module_index: int,
+                            mounting_location: jax.typing.ArrayLike,
+                            X: jax.typing.ArrayLike, U: jax.typing.ArrayLike):
     X_module = X[module_index * 2:(module_index + 1) * 2]
     Is = U[2 * module_index + 0]
     Id = U[2 * module_index + 1]
 
-    Rthetaplusthetas = R(X[dynamics.VELOCITY_STATE_THETA] +
-                         X_module[dynamics.VELOCITY_STATE_THETAS0])
+    rotated_mounting_location = Rtheta @ mounting_location
+
+    Rthetaplusthetas = R(X[VELOCITY_STATE_THETA] +
+                         X_module[VELOCITY_STATE_THETAS0])
 
     caster_vector = jax.numpy.array([-coefficients.caster, 0.0])
 
-    robot_velocity = X[dynamics.VELOCITY_STATE_VX:dynamics.VELOCITY_STATE_VY +
-                       1]
+    robot_velocity = X[VELOCITY_STATE_VX:VELOCITY_STATE_VY + 1]
 
     contact_patch_velocity = (
-        angle_cross(Rtheta @ mounting_location,
-                    X[dynamics.VELOCITY_STATE_OMEGA]) + robot_velocity +
-        angle_cross(Rthetaplusthetas @ caster_vector,
-                    (X[dynamics.VELOCITY_STATE_OMEGA] +
-                     X_module[dynamics.VELOCITY_STATE_OMEGAS0])))
+        angle_cross(rotated_mounting_location, X[VELOCITY_STATE_OMEGA]) +
+        robot_velocity + angle_cross(
+            Rthetaplusthetas @ caster_vector,
+            (X[VELOCITY_STATE_OMEGA] + X_module[VELOCITY_STATE_OMEGAS0])))
 
+    # Velocity of the contact patch over the field projected into the direction
+    # of the wheel.
     wheel_ground_velocity = Rthetaplusthetas.T @ contact_patch_velocity
 
     slip_angle = jax.numpy.sin(
@@ -288,11 +291,11 @@
 
     F = Rthetaplusthetas @ jax.numpy.array([Fwx, Fwy])
 
-    torque = force_cross(Rtheta @ mounting_location, F)
+    torque = force_cross(rotated_mounting_location, F)
 
     X_dot_contribution = jax.numpy.hstack((jax.numpy.zeros(
         (2, )), ) * (module_index) + (jax.numpy.array([
-            X_module[dynamics.VELOCITY_STATE_OMEGAS0],
+            X_module[VELOCITY_STATE_OMEGAS0],
             alphas,
         ]), ) + (jax.numpy.zeros((2, )), ) * (3 - module_index) + (
             jax.numpy.zeros((1, )),
@@ -300,29 +303,30 @@
             jax.numpy.array([torque / coefficients.J]),
         ))
 
-    return X_dot_contribution
+    return X_dot_contribution, F, torque
 
 
 @partial(jax.jit, static_argnames=['coefficients'])
-def velocity_dynamics(coefficients: CoefficientsType, X, U):
-    Rtheta = R(X[dynamics.VELOCITY_STATE_THETA])
+def velocity_dynamics(coefficients: CoefficientsType, X: jax.typing.ArrayLike,
+                      U: jax.typing.ArrayLike):
+    Rtheta = R(X[VELOCITY_STATE_THETA])
 
-    module0 = velocity_module_physics(
+    module0, _, _ = velocity_module_physics(
         coefficients, Rtheta, 0,
         jax.numpy.array(
             [coefficients.robot_width / 2.0, coefficients.robot_width / 2.0]),
         X, U)
-    module1 = velocity_module_physics(
+    module1, _, _ = velocity_module_physics(
         coefficients, Rtheta, 1,
         jax.numpy.array(
             [-coefficients.robot_width / 2.0, coefficients.robot_width / 2.0]),
         X, U)
-    module2 = velocity_module_physics(
+    module2, _, _ = velocity_module_physics(
         coefficients, Rtheta, 2,
         jax.numpy.array(
             [-coefficients.robot_width / 2.0,
              -coefficients.robot_width / 2.0]), X, U)
-    module3 = velocity_module_physics(
+    module3, _, _ = velocity_module_physics(
         coefficients, Rtheta, 3,
         jax.numpy.array(
             [coefficients.robot_width / 2.0, -coefficients.robot_width / 2.0]),
@@ -330,5 +334,92 @@
 
     X_dot = module0 + module1 + module2 + module3
 
-    return X_dot.at[dynamics.VELOCITY_STATE_THETA].set(
-        X[dynamics.VELOCITY_STATE_OMEGA])
+    return X_dot.at[VELOCITY_STATE_THETA].set(X[VELOCITY_STATE_OMEGA])
+
+
+def to_velocity_state(X):
+    return jax.numpy.array([
+        X[STATE_THETAS0],
+        X[STATE_OMEGAS0],
+        X[STATE_THETAS1],
+        X[STATE_OMEGAS1],
+        X[STATE_THETAS2],
+        X[STATE_OMEGAS2],
+        X[STATE_THETAS3],
+        X[STATE_OMEGAS3],
+        X[STATE_THETA],
+        X[STATE_VX],
+        X[STATE_VY],
+        X[STATE_OMEGA],
+    ])
+
+
+@jax.jit
+def mpc_cost(coefficients: CoefficientsType, X, U, goal):
+    J = 0
+
+    rnorm = jax.numpy.linalg.norm(goal[0:2])
+
+    vnorm = jax.lax.select(rnorm > 0.0001, goal[0:2] / rnorm,
+                           jax.numpy.array([1.0, 0.0]))
+    vperp = jax.lax.select(rnorm > 0.0001,
+                           jax.numpy.array([-vnorm[1], vnorm[0]]),
+                           jax.numpy.array([0.0, 1.0]))
+
+    velocity_error = goal[0:2] - X[VELOCITY_STATE_VX:VELOCITY_STATE_VY + 1]
+
+    # TODO(austin): Do we want to do something more special for 0?
+
+    J += 75 * (jax.numpy.dot(velocity_error, vnorm)**2.0)
+    J += 1500 * (jax.numpy.dot(velocity_error, vperp)**2.0)
+    J += 1000 * (goal[2] - X[VELOCITY_STATE_OMEGA])**2.0
+
+    kSteerVelocityGain = 0.10
+    J += kSteerVelocityGain * (X[VELOCITY_STATE_OMEGAS0])**2.0
+    J += kSteerVelocityGain * (X[VELOCITY_STATE_OMEGAS1])**2.0
+    J += kSteerVelocityGain * (X[VELOCITY_STATE_OMEGAS2])**2.0
+    J += kSteerVelocityGain * (X[VELOCITY_STATE_OMEGAS3])**2.0
+
+    mounting_locations = jax.numpy.array(
+        [[coefficients.robot_width / 2.0, coefficients.robot_width / 2.0],
+         [-coefficients.robot_width / 2.0, coefficients.robot_width / 2.0],
+         [-coefficients.robot_width / 2.0, -coefficients.robot_width / 2.0],
+         [coefficients.robot_width / 2.0, -coefficients.robot_width / 2.0]])
+
+    Rtheta = R(X[VELOCITY_STATE_THETA])
+    _, F0, torque0 = velocity_module_physics(coefficients, Rtheta, 0,
+                                             mounting_locations[0], X, U)
+    _, F1, torque1 = velocity_module_physics(coefficients, Rtheta, 1,
+                                             mounting_locations[1], X, U)
+    _, F2, torque2 = velocity_module_physics(coefficients, Rtheta, 2,
+                                             mounting_locations[2], X, U)
+    _, F3, torque3 = velocity_module_physics(coefficients, Rtheta, 3,
+                                             mounting_locations[3], X, U)
+
+    forces = [F0, F1, F2, F3]
+
+    F = (F0 + F1 + F2 + F3)
+    torque = (torque0 + torque1 + torque2 + torque3)
+
+    def force_cross(torque, r):
+        r_squared_norm = jax.numpy.inner(r, r)
+
+        return jax.numpy.array(
+            [-r[1] * torque / r_squared_norm, r[0] * torque / r_squared_norm])
+
+    # TODO(austin): Are these penalties reasonable?  Do they give us a decent time constant?
+    for i in range(4):
+        desired_force = F / 4.0 + force_cross(
+            torque / 4.0, Rtheta @ mounting_locations[i, :])
+        force_error = desired_force - forces[i]
+        J += 0.01 * jax.numpy.inner(force_error, force_error)
+
+    for i in range(4):
+        Is = U[2 * i + 0]
+        Id = U[2 * i + 1]
+        # Steer
+        J += ((Is + STEER_CURRENT_COUPLING_FACTOR * Id)**2.0) / 100000.0
+        # Drive
+        J += (Id**2.0) / 1000.0
+
+    return J
diff --git a/frc971/control_loops/swerve/multi_experience_collector.py b/frc971/control_loops/swerve/multi_experience_collector.py
new file mode 100644
index 0000000..d0551e1
--- /dev/null
+++ b/frc971/control_loops/swerve/multi_experience_collector.py
@@ -0,0 +1,54 @@
+#!/usr/bin/env python3
+from absl import app
+from absl import flags
+import sys
+from multiprocessing.pool import ThreadPool
+import pathlib
+import subprocess
+
+FLAGS = flags.FLAGS
+flags.DEFINE_string('outdir', '/tmp/swerve', "Directory to write results to.")
+flags.DEFINE_integer('num_actors', 20, 'Number of actors to run in parallel.')
+flags.DEFINE_integer('num_solutions', 100,
+                     'Number of random problems to solve.')
+
+
+def collect_experience(agent_number):
+    filename = f'{agent_number}'
+    if FLAGS.outdir:
+        subdir = pathlib.Path(FLAGS.outdir) / filename
+    else:
+        subdir = pathlib.Path(filename)
+    subdir.mkdir(parents=True, exist_ok=True)
+
+    with open(f'{subdir.resolve()}/log', 'w') as output:
+        subprocess.check_call(
+            args=[
+                sys.executable,
+                "frc971/control_loops/swerve/experience_collector",
+                f"--seed={agent_number}",
+                f"--outputdir={subdir.resolve()}",
+                "--quiet",
+                f"--num_solutions={FLAGS.num_solutions}",
+            ],
+            stdout=output,
+            stderr=output,
+        )
+
+
+def main(argv):
+    # Load a simple problem first so we compile with less system load.  This
+    # makes it faster on a processor with frequency boosting.
+    subprocess.check_call(args=[
+        sys.executable,
+        "frc971/control_loops/swerve/experience_collector",
+        "--compileonly",
+    ])
+
+    # Try a bunch of goals now
+    with ThreadPool(FLAGS.num_actors) as pool:
+        pool.starmap(collect_experience, zip(range(FLAGS.num_actors), ))
+
+
+if __name__ == '__main__':
+    app.run(main)
diff --git a/frc971/control_loops/swerve/physics_test.py b/frc971/control_loops/swerve/physics_test.py
index 31b96c9..bc366fa 100644
--- a/frc971/control_loops/swerve/physics_test.py
+++ b/frc971/control_loops/swerve/physics_test.py
@@ -18,6 +18,7 @@
 from frc971.control_loops.swerve import dynamics
 from frc971.control_loops.swerve import nocaster_dynamics
 from frc971.control_loops.swerve import physics_test_utils as utils
+from frc971.control_loops.swerve import casadi_velocity_mpc_lib
 from frc971.control_loops.swerve import jax_dynamics
 from frc971.control_loops.swerve.cpp_dynamics import swerve_dynamics as cpp_dynamics
 
@@ -60,6 +61,7 @@
         Xdot = self.position_swerve_full_dynamics(X, U)
         Xdot_jax = jax_dynamics.full_dynamics(self.coefficients, X[:, 0], U[:,
                                                                             0])
+        self.assertEqual(Xdot.shape[0], Xdot_jax.shape[0])
 
         self.assertLess(
             numpy.linalg.norm(Xdot[:, 0] - Xdot_jax),
@@ -72,6 +74,9 @@
         velocity_physics_jax = jax_dynamics.velocity_dynamics(
             self.coefficients, X_velocity[:, 0], U[:, 0])
 
+        self.assertEqual(velocity_physics.shape[0],
+                         velocity_physics_jax.shape[0])
+
         self.assertLess(
             numpy.linalg.norm(velocity_physics[:, 0] - velocity_physics_jax),
             2e-8,
@@ -703,8 +708,56 @@
         Xdot_rot = self.swerve_full_dynamics(X_rot, steer_I, skip_compare=True)
 
         self.assertGreater(Xdot[dynamics.STATE_OMEGA, 0], 0.0)
-        self.assertAlmostEquals(Xdot[dynamics.STATE_OMEGA, 0],
-                                Xdot_rot[dynamics.STATE_OMEGA, 0])
+        self.assertAlmostEqual(Xdot[dynamics.STATE_OMEGA, 0],
+                               Xdot_rot[dynamics.STATE_OMEGA, 0])
+
+    def test_cost_equality(self):
+        """Tests that the casadi and jax cost functions match."""
+        mpc = casadi_velocity_mpc_lib.MPC(jit=False)
+        cost = mpc.make_cost()
+
+        for i in range(10):
+            X = numpy.random.uniform(size=(dynamics.NUM_VELOCITY_STATES, ))
+            U = numpy.random.uniform(low=-10, high=10, size=(8, ))
+            R = numpy.random.uniform(low=-1, high=1, size=(3, ))
+
+            J = numpy.array(cost(X, U, R))[0, 0]
+            jax_J = jax_dynamics.mpc_cost(self.coefficients, X, U, R)
+
+            self.assertAlmostEqual(J, jax_J)
+
+        R = jax.numpy.array([0.0, 0.0, 1.0])
+
+        # Now try spinning in place and make sure the cost doesn't change.
+        # This tells us if we got our rotations right.
+        steer_I = numpy.array([(i % 2) * 20 for i in range(8)])
+
+        X = utils.state_vector(velocity=numpy.array([[0.0], [0.0]]),
+                               omega=0.0,
+                               module_angles=[
+                                   3 * numpy.pi / 4.0, -3 * numpy.pi / 4.0,
+                                   -numpy.pi / 4.0, numpy.pi / 4.0
+                               ],
+                               drive_wheel_velocity=1.0)
+
+        jax_J_orig = jax_dynamics.mpc_cost(self.coefficients,
+                                           self.to_velocity_state(X)[:, 0],
+                                           steer_I, R)
+
+        X_rotated = utils.state_vector(velocity=numpy.array([[0.0], [0.0]]),
+                                       omega=0.0,
+                                       theta=numpy.pi,
+                                       module_angles=[
+                                           3 * numpy.pi / 4.0,
+                                           -3 * numpy.pi / 4.0,
+                                           -numpy.pi / 4.0, numpy.pi / 4.0
+                                       ],
+                                       drive_wheel_velocity=1.0)
+        jax_J_rotated = jax_dynamics.mpc_cost(
+            self.coefficients,
+            self.to_velocity_state(X_rotated)[:, 0], steer_I, R)
+
+        self.assertAlmostEqual(jax_J_orig, jax_J_rotated)
 
     def test_cpp_consistency(self):
         """Tests that the C++ physics are consistent with the Python physics."""
diff --git a/frc971/control_loops/swerve/velocity_controller/BUILD b/frc971/control_loops/swerve/velocity_controller/BUILD
index 5e06420..a0078b6 100644
--- a/frc971/control_loops/swerve/velocity_controller/BUILD
+++ b/frc971/control_loops/swerve/velocity_controller/BUILD
@@ -22,3 +22,86 @@
         "@pip//jax",
     ],
 )
+
+py_binary(
+    name = "main",
+    srcs = [
+        "main.py",
+        "model.py",
+        "train.py",
+    ],
+    deps = [
+        ":experience_buffer",
+        ":physics",
+        "//frc971/control_loops/swerve:jax_dynamics",
+        "@pip//absl_py",
+        "@pip//aim",
+        "@pip//clu",
+        "@pip//flashbax",
+        "@pip//flax",
+        "@pip//jax",
+        "@pip//jaxtyping",
+        "@pip//matplotlib",
+        "@pip//numpy",
+        "@pip//tensorflow",
+        "@pip//tensorflow_probability",
+        "@pip//tf_keras",
+    ],
+)
+
+py_library(
+    name = "physics",
+    srcs = ["physics.py"],
+    deps = [
+        "//frc971/control_loops/swerve:jax_dynamics",
+        "@pip//flax",
+        "@pip//jax",
+        "@pip//jaxtyping",
+    ],
+)
+
+py_binary(
+    name = "plot",
+    srcs = [
+        "model.py",
+        "plot.py",
+    ],
+    deps = [
+        ":experience_buffer",
+        ":physics",
+        "//frc971/control_loops/swerve:jax_dynamics",
+        "@pip//absl_py",
+        "@pip//flashbax",
+        "@pip//flax",
+        "@pip//jax",
+        "@pip//jaxtyping",
+        "@pip//matplotlib",
+        "@pip//numpy",
+        "@pip//pygobject",
+        "@pip//tensorflow",
+        "@pip//tensorflow_probability",
+        "@pip//tf_keras",
+    ],
+)
+
+py_binary(
+    name = "lqr_plot",
+    srcs = [
+        "lqr_plot.py",
+        "model.py",
+    ],
+    deps = [
+        ":experience_buffer",
+        ":physics",
+        "//frc971/control_loops/swerve:jax_dynamics",
+        "@pip//absl_py",
+        "@pip//flashbax",
+        "@pip//flax",
+        "@pip//jax",
+        "@pip//jaxtyping",
+        "@pip//matplotlib",
+        "@pip//numpy",
+        "@pip//pygobject",
+        "@pip//tensorflow",
+    ],
+)
diff --git a/frc971/control_loops/swerve/velocity_controller/lqr_plot.py b/frc971/control_loops/swerve/velocity_controller/lqr_plot.py
new file mode 100644
index 0000000..a63e100
--- /dev/null
+++ b/frc971/control_loops/swerve/velocity_controller/lqr_plot.py
@@ -0,0 +1,538 @@
+#!/usr/bin/env python3
+
+import os
+
+# Setup JAX to run on the CPU
+os.environ['XLA_FLAGS'] = ' '.join([
+    # Teach it where to find CUDA
+    '--xla_gpu_cuda_data_dir=/usr/lib/cuda',
+    # Use up to 20 cores
+    '--xla_force_host_platform_device_count=20',
+    # Dump XLA to /tmp/foo to aid debugging
+    '--xla_dump_to=/tmp/foo',
+    '--xla_gpu_enable_command_buffer='
+])
+
+os.environ['JAX_PLATFORMS'] = 'cpu'
+# Don't pre-allocate memory
+os.environ['XLA_PYTHON_CLIENT_PREALLOCATE'] = 'false'
+
+import absl
+from absl import logging
+from matplotlib.animation import FuncAnimation
+import matplotlib
+import numpy
+import scipy
+import time
+
+matplotlib.use("gtk3agg")
+
+from matplotlib import pylab
+from matplotlib import pyplot
+from flax.training import checkpoints
+from frc971.control_loops.python import controls
+import tensorflow as tf
+import threading
+import collections
+
+import jax
+
+jax._src.deprecations.accelerate('tracer-hash')
+jax.config.update("jax_compilation_cache_dir", "/tmp/jax_cache")
+jax.config.update("jax_persistent_cache_min_entry_size_bytes", -1)
+jax.config.update("jax_persistent_cache_min_compile_time_secs", 0)
+
+from frc971.control_loops.swerve.velocity_controller.model import *
+from frc971.control_loops.swerve.velocity_controller.physics import *
+
+# Container for the data.
+Data = collections.namedtuple('Data', [
+    't',
+    'X',
+    'X_lqr',
+    'U',
+    'U_lqr',
+    'cost',
+    'cost_lqr',
+    'q1_grid',
+    'q2_grid',
+    'q_grid',
+    'target_q_grid',
+    'lqr_grid',
+    'pi_grid_U',
+    'lqr_grid_U',
+    'grid_X',
+    'grid_Y',
+    'reward',
+    'reward_lqr',
+    'step',
+    'stdev',
+])
+
+FLAGS = absl.flags.FLAGS
+
+absl.flags.DEFINE_string('workdir', None, 'Directory to store model data.')
+
+absl.flags.DEFINE_integer(
+    'horizon',
+    default=100,
+    help='Horizon to simulate',
+)
+
+absl.flags.DEFINE_float(
+    'alpha',
+    default=0.2,
+    help='Entropy.  If negative, automatically solve for it.',
+)
+
+numpy.set_printoptions(linewidth=200, )
+
+
+def restore_checkpoint(state: TrainState, workdir: str):
+    return checkpoints.restore_checkpoint(workdir, state)
+
+
+def generate_data(step=None):
+    grid_X = numpy.arange(-1, 1, 0.1)
+    grid_Y = numpy.arange(-10, 10, 0.1)
+    grid_X, grid_Y = numpy.meshgrid(grid_X, grid_Y)
+    grid_X = jax.numpy.array(grid_X)
+    grid_Y = jax.numpy.array(grid_Y)
+    # Load the training state.
+    problem = physics.TurretProblem()
+
+    rng = jax.random.key(0)
+    rng, init_rng = jax.random.split(rng)
+
+    state = create_train_state(
+        init_rng,
+        problem,
+        q_learning_rate=FLAGS.q_learning_rate,
+        pi_learning_rate=FLAGS.pi_learning_rate,
+        alpha_learning_rate=FLAGS.alpha_learning_rate,
+    )
+
+    state = restore_checkpoint(state, FLAGS.workdir)
+    if step is not None and state.step == step:
+        return None
+
+    X = jax.numpy.array([1.0, 0.0])
+    X_lqr = X.copy()
+    goal = jax.numpy.array([0.0, 0.0])
+
+    logging.info('X: %s', X)
+    logging.info('goal: %s', goal)
+    logging.debug('params: %s', state.params)
+
+    # Compute the various cost surfaces for plotting.
+    def compute_q1(X, Y):
+        return state.q1_apply(
+            state.params,
+            observation=state.problem.unwrap_angles(jax.numpy.array([X, Y])),
+            R=goal,
+            action=jax.numpy.array([0.]),
+        )[0]
+
+    def compute_q2(X, Y):
+        return state.q2_apply(
+            state.params,
+            observation=state.problem.unwrap_angles(jax.numpy.array([X, Y])),
+            R=goal,
+            action=jax.numpy.array([0.]),
+        )[0]
+
+    def lqr_cost(X, Y):
+        x = jax.numpy.array([X, Y]) - goal
+        return -x.T @ jax.numpy.array(problem.P) @ x
+
+    def compute_q(params, x, y):
+        X = state.problem.unwrap_angles(jax.numpy.array([x, y]))
+
+        return jax.numpy.minimum(
+            state.q1_apply(
+                params,
+                observation=X,
+                R=goal,
+                action=jax.numpy.array([0.]),
+            )[0],
+            state.q2_apply(
+                params,
+                observation=X,
+                R=goal,
+                action=jax.numpy.array([0.]),
+            )[0])
+
+    cost_grid1 = jax.vmap(jax.vmap(compute_q1))(grid_X, grid_Y)
+    cost_grid2 = jax.vmap(jax.vmap(compute_q2))(grid_X, grid_Y)
+    cost_grid = jax.vmap(jax.vmap(lambda x, y: compute_q(state.params, x, y)))(
+        grid_X, grid_Y)
+    target_cost_grid = jax.vmap(
+        jax.vmap(lambda x, y: compute_q(state.target_params, x, y)))(grid_X,
+                                                                     grid_Y)
+    lqr_cost_grid = jax.vmap(jax.vmap(lqr_cost))(grid_X, grid_Y)
+
+    # Now compute the two controller surfaces.
+    def compute_lqr_U(X, Y):
+        x = jax.numpy.array([X, Y])
+        return (-jax.numpy.array(problem.F.reshape((2, ))) @ x)[0]
+
+    def compute_pi_U(X, Y):
+        x = jax.numpy.array([X, Y])
+        U, _, _ = state.pi_apply(rng,
+                                 state.params,
+                                 observation=state.problem.unwrap_angles(x),
+                                 R=goal,
+                                 deterministic=True)
+        return U[0] * problem.action_limit
+
+    def compute_pi_stdev(X, Y):
+        x = jax.numpy.array([X, Y])
+        _, _, std = state.pi_apply(rng,
+                                   state.params,
+                                   observation=state.problem.unwrap_angles(x),
+                                   R=goal,
+                                   deterministic=True)
+        return std[0]
+
+    std_grid = jax.vmap(jax.vmap(compute_pi_stdev))(grid_X, grid_Y)
+
+    lqr_cost_U = jax.vmap(jax.vmap(compute_lqr_U))(grid_X, grid_Y)
+    pi_cost_U = jax.vmap(jax.vmap(compute_pi_U))(grid_X, grid_Y)
+
+    logging.info('Finished cost')
+
+    # Now simulate the robot, accumulating up things to plot.
+    def loop(i, val):
+        X, X_lqr, data, params = val
+        t = data.t.at[i].set(i * problem.dt)
+
+        normalized_U, _, _ = state.pi_apply(
+            rng,
+            params,
+            observation=state.problem.unwrap_angles(X),
+            R=goal,
+            deterministic=True)
+        U_lqr = problem.F @ (goal - X_lqr)
+
+        cost = jax.numpy.minimum(
+            state.q1_apply(params,
+                           observation=state.problem.unwrap_angles(X),
+                           R=goal,
+                           action=normalized_U),
+            state.q2_apply(params,
+                           observation=state.problem.unwrap_angles(X),
+                           R=goal,
+                           action=normalized_U))
+
+        U = normalized_U * problem.action_limit
+
+        U_plot = data.U.at[i, :].set(U)
+        U_lqr_plot = data.U_lqr.at[i, :].set(U_lqr)
+        X_plot = data.X.at[i, :].set(X)
+        X_lqr_plot = data.X_lqr.at[i, :].set(X_lqr)
+        cost_plot = data.cost.at[i, :].set(cost)
+        cost_lqr_plot = data.cost_lqr.at[i, :].set(lqr_cost(*X_lqr))
+
+        X = problem.A @ X + problem.B @ U
+        X_lqr = problem.A @ X_lqr + problem.B @ U_lqr
+
+        reward = data.reward + state.problem.reward(X, normalized_U, goal)
+        reward_lqr = data.reward_lqr + state.problem.reward(
+            X_lqr, U_lqr / problem.action_limit, goal)
+
+        return X, X_lqr, data._replace(
+            t=t,
+            U=U_plot,
+            U_lqr=U_lqr_plot,
+            X=X_plot,
+            X_lqr=X_lqr_plot,
+            cost=cost_plot,
+            cost_lqr=cost_lqr_plot,
+            reward=reward,
+            reward_lqr=reward_lqr,
+        ), params
+
+    # Do it.
+    @jax.jit
+    def integrate(data, X, X_lqr, params):
+        return jax.lax.fori_loop(0, FLAGS.horizon, loop,
+                                 (X, X_lqr, data, params))
+
+    X, X_lqr, data, params = integrate(
+        Data(
+            t=jax.numpy.zeros((FLAGS.horizon, )),
+            X=jax.numpy.zeros((FLAGS.horizon, state.problem.num_states)),
+            X_lqr=jax.numpy.zeros((FLAGS.horizon, state.problem.num_states)),
+            U=jax.numpy.zeros((FLAGS.horizon, state.problem.num_outputs)),
+            U_lqr=jax.numpy.zeros((FLAGS.horizon, state.problem.num_outputs)),
+            cost=jax.numpy.zeros((FLAGS.horizon, 1)),
+            cost_lqr=jax.numpy.zeros((FLAGS.horizon, 1)),
+            q1_grid=cost_grid1,
+            q2_grid=cost_grid2,
+            q_grid=cost_grid,
+            target_q_grid=target_cost_grid,
+            lqr_grid=lqr_cost_grid,
+            pi_grid_U=pi_cost_U,
+            lqr_grid_U=lqr_cost_U,
+            grid_X=grid_X,
+            grid_Y=grid_Y,
+            reward=0.0,
+            reward_lqr=0.0,
+            step=state.step,
+            stdev=std_grid,
+        ), X, X_lqr, state.params)
+
+    logging.info('Finished integrating, reward of %f, lqr reward of %f',
+                 data.reward, data.reward_lqr)
+
+    # Convert back to numpy for plotting.
+    return Data(
+        t=numpy.array(data.t),
+        X=numpy.array(data.X),
+        X_lqr=numpy.array(data.X_lqr),
+        U=numpy.array(data.U),
+        U_lqr=numpy.array(data.U_lqr),
+        cost=numpy.array(data.cost),
+        cost_lqr=numpy.array(data.cost_lqr),
+        q1_grid=numpy.array(data.q1_grid),
+        q2_grid=numpy.array(data.q2_grid),
+        q_grid=numpy.array(data.q_grid),
+        target_q_grid=numpy.array(data.target_q_grid),
+        lqr_grid=numpy.array(data.lqr_grid),
+        pi_grid_U=numpy.array(data.pi_grid_U),
+        lqr_grid_U=numpy.array(data.lqr_grid_U),
+        grid_X=numpy.array(data.grid_X),
+        grid_Y=numpy.array(data.grid_Y),
+        stdev=numpy.array(data.stdev),
+        reward=float(data.reward),
+        reward_lqr=float(data.reward_lqr),
+        step=data.step,
+    )
+
+
+class Plotter(object):
+
+    def __init__(self, data):
+        # Make all the plots and axis.
+        self.fig0, self.axs0 = pylab.subplots(3)
+        self.fig0.supxlabel('Seconds')
+
+        self.axs_velocity = self.axs0[0].twinx()
+
+        self.x, = self.axs0[0].plot([], [], label="x")
+        self.x_lqr, = self.axs0[0].plot([], [], label="x_lqr")
+
+        self.axs0[0].set_ylabel('Position')
+        self.axs0[0].legend()
+        self.axs0[0].grid()
+
+        self.v, = self.axs_velocity.plot([], [], label="v", color='C2')
+        self.v_lqr, = self.axs_velocity.plot([], [], label="v_lqr", color='C3')
+        self.axs_velocity.set_ylabel('Velocity')
+        self.axs_velocity.legend()
+
+        self.uaxis, = self.axs0[1].plot([], [], label="U")
+        self.uaxis_lqr, = self.axs0[1].plot([], [], label="U_lqr")
+
+        self.axs0[1].set_ylabel('Amps')
+        self.axs0[1].legend()
+        self.axs0[1].grid()
+
+        self.costaxis, = self.axs0[2].plot([], [], label="cost")
+        self.costlqraxis, = self.axs0[2].plot([], [], label="cost lqr")
+        self.axs0[2].set_ylabel('Cost')
+        self.axs0[2].legend()
+        self.axs0[2].grid()
+
+        self.costfig = pyplot.figure(figsize=pyplot.figaspect(0.5))
+        self.cost3dax = [
+            self.costfig.add_subplot(2, 3, 1, projection='3d'),
+            self.costfig.add_subplot(2, 3, 2, projection='3d'),
+            self.costfig.add_subplot(2, 3, 3, projection='3d'),
+            self.costfig.add_subplot(2, 3, 4, projection='3d'),
+            self.costfig.add_subplot(2, 3, 5, projection='3d'),
+            self.costfig.add_subplot(2, 3, 6, projection='3d'),
+        ]
+
+        self.Ufig = pyplot.figure(figsize=pyplot.figaspect(0.5))
+        self.Uax = [
+            self.Ufig.add_subplot(2, 2, 1, projection='3d'),
+            self.Ufig.add_subplot(2, 2, 2, projection='3d'),
+            self.Ufig.add_subplot(2, 2, 3, projection='3d'),
+            self.Ufig.add_subplot(2, 2, 4, projection='3d'),
+        ]
+
+        self.last_trajectory_step = 0
+        self.last_cost_step = 0
+        self.last_U_step = 0
+
+    def update_trajectory_plot(self, data):
+        if data.step == self.last_trajectory_step:
+            return
+        self.last_trajectory_step = data.step
+        logging.info('Updating trajectory plots')
+        self.fig0.suptitle(f'Step {data.step}')
+
+        # Put data in the trajectory plots.
+        self.x.set_data(data.t, data.X[:, 0])
+        self.v.set_data(data.t, data.X[:, 1])
+        self.x_lqr.set_data(data.t, data.X_lqr[:, 0])
+        self.v_lqr.set_data(data.t, data.X_lqr[:, 1])
+
+        self.uaxis.set_data(data.t, data.U[:, 0])
+        self.uaxis_lqr.set_data(data.t, data.U_lqr[:, 0])
+        self.costaxis.set_data(data.t, data.cost[:, 0] - data.cost[-1, 0])
+        self.costlqraxis.set_data(data.t, data.cost_lqr[:, 0])
+
+        self.axs0[0].relim()
+        self.axs0[0].autoscale_view()
+
+        self.axs_velocity.relim()
+        self.axs_velocity.autoscale_view()
+
+        self.axs0[1].relim()
+        self.axs0[1].autoscale_view()
+
+        self.axs0[2].relim()
+        self.axs0[2].autoscale_view()
+
+        return self.x, self.v, self.uaxis, self.costaxis, self.costlqraxis
+
+    def update_cost_plot(self, data):
+        if data.step == self.last_cost_step:
+            return
+        logging.info('Updating cost plots')
+        self.last_cost_step = data.step
+        self.costfig.suptitle(f'Step {data.step}')
+        # Put data in the cost plots.
+        if hasattr(self, 'costsurf'):
+            for surf in self.costsurf:
+                surf.remove()
+
+        plots = [
+            (data.q1_grid, 'q1'),
+            (data.q2_grid, 'q2'),
+            (data.q_grid, 'q'),
+            (data.target_q_grid, 'target q'),
+            (data.lqr_grid, 'lqr'),
+            (data.q_grid - data.q_grid.max() - data.lqr_grid, 'error'),
+        ]
+
+        self.costsurf = [
+            self.cost3dax[i].plot_surface(
+                data.grid_X,
+                data.grid_Y,
+                Z,
+                cmap="magma",
+                label=label,
+            ) for i, (Z, label) in enumerate(plots)
+        ]
+
+        for axis in self.cost3dax:
+            axis.legend()
+            axis.relim()
+            axis.autoscale_view()
+
+        return self.costsurf
+
+    def update_U_plot(self, data):
+        if data.step == self.last_U_step:
+            return
+        self.last_U_step = data.step
+        logging.info('Updating U plots')
+        self.Ufig.suptitle(f'Step {data.step}')
+        # Put data in the controller plots.
+        if hasattr(self, 'Usurf'):
+            for surf in self.Usurf:
+                surf.remove()
+
+        plots = [
+            (data.lqr_grid_U, 'lqr'),
+            (data.pi_grid_U, 'pi'),
+            ((data.lqr_grid_U - data.pi_grid_U), 'error'),
+            (data.stdev, 'stdev'),
+        ]
+
+        self.Usurf = [
+            self.Uax[i].plot_surface(
+                data.grid_X,
+                data.grid_Y,
+                Z,
+                cmap="magma",
+                label=label,
+            ) for i, (Z, label) in enumerate(plots)
+        ]
+
+        for axis in self.Uax:
+            axis.legend()
+            axis.relim()
+            axis.autoscale_view()
+
+        return self.Usurf
+
+
+def main(argv):
+    if len(argv) > 1:
+        raise absl.app.UsageError('Too many command-line arguments.')
+
+    tf.config.experimental.set_visible_devices([], 'GPU')
+
+    lock = threading.Lock()
+
+    # Load data.
+    data = generate_data()
+
+    plotter = Plotter(data)
+
+    # Event for shutting down the thread.
+    shutdown = threading.Event()
+
+    # Thread to grab new data periodically.
+    def do_update():
+        while True:
+            nonlocal data
+
+            my_data = generate_data(data.step)
+
+            if my_data is not None:
+                with lock:
+                    data = my_data
+
+            if shutdown.wait(timeout=3):
+                return
+
+    update_thread = threading.Thread(target=do_update)
+    update_thread.start()
+
+    # Now, update each of the plots every second with the new data.
+    def update0(frame):
+        with lock:
+            my_data = data
+
+        return plotter.update_trajectory_plot(my_data)
+
+    def update1(frame):
+        with lock:
+            my_data = data
+
+        return plotter.update_cost_plot(my_data)
+
+    def update2(frame):
+        with lock:
+            my_data = data
+
+        return plotter.update_U_plot(my_data)
+
+    animation0 = FuncAnimation(plotter.fig0, update0, interval=1000)
+    animation1 = FuncAnimation(plotter.costfig, update1, interval=1000)
+    animation2 = FuncAnimation(plotter.Ufig, update2, interval=1000)
+
+    pyplot.show()
+
+    shutdown.set()
+    update_thread.join()
+
+
+if __name__ == '__main__':
+    absl.flags.mark_flags_as_required(['workdir'])
+    absl.app.run(main)
diff --git a/frc971/control_loops/swerve/velocity_controller/main.py b/frc971/control_loops/swerve/velocity_controller/main.py
new file mode 100644
index 0000000..391b0fe
--- /dev/null
+++ b/frc971/control_loops/swerve/velocity_controller/main.py
@@ -0,0 +1,81 @@
+import os
+
+# Setup XLA first.
+os.environ['XLA_FLAGS'] = ' '.join([
+    # Teach it where to find CUDA
+    '--xla_gpu_cuda_data_dir=/usr/lib/cuda',
+    # Use up to 20 cores
+    #'--xla_force_host_platform_device_count=6',
+    # Dump XLA to /tmp/foo to aid debugging
+    #'--xla_dump_to=/tmp/foo',
+    #'--xla_gpu_enable_command_buffer='
+    # Dump sharding
+    #"--xla_dump_to=/tmp/foo",
+    #"--xla_dump_hlo_pass_re=spmd|propagation"
+])
+os.environ['JAX_PLATFORMS'] = 'cuda,cpu'
+os.environ['XLA_PYTHON_CLIENT_PREALLOCATE'] = 'true'
+os.environ['XLA_PYTHON_CLIENT_MEM_FRACTION'] = '.50'
+
+from absl import app
+from absl import flags
+from absl import logging
+from clu import platform
+import jax
+import tensorflow as tf
+from frc971.control_loops.swerve import jax_dynamics
+from frc971.control_loops.swerve.velocity_controller import physics
+
+jax._src.deprecations.accelerate('tracer-hash')
+# Enable the compilation cache
+jax.config.update("jax_compilation_cache_dir", "/tmp/jax_cache")
+jax.config.update("jax_persistent_cache_min_entry_size_bytes", -1)
+jax.config.update("jax_persistent_cache_min_compile_time_secs", 0)
+jax.config.update('jax_threefry_partitionable', True)
+
+import train
+
+FLAGS = flags.FLAGS
+
+flags.DEFINE_string('workdir', None, 'Directory to store model data.')
+
+flags.DEFINE_bool('swerve', True,
+                  'If true, train the swerve model, otherwise do the turret.')
+
+
+def main(argv):
+    if len(argv) > 1:
+        raise app.UsageError('Too many command-line arguments.')
+
+    # Hide any GPUs from TensorFlow. Otherwise it might reserve memory.
+    tf.config.experimental.set_visible_devices([], 'GPU')
+
+    logging.info('JAX process: %d / %d', jax.process_index(),
+                 jax.process_count())
+    logging.info('JAX local devices: %r', jax.local_devices())
+
+    # Add a note so that we can tell which task is which JAX host.
+    # (Depending on the platform task 0 is not guaranteed to be host 0)
+    platform.work_unit().set_task_status(
+        f'process_index: {jax.process_index()}, '
+        f'process_count: {jax.process_count()}')
+    platform.work_unit().create_artifact(platform.ArtifactType.DIRECTORY,
+                                         FLAGS.workdir, 'workdir')
+
+    logging.info(
+        'Visualize results with: bazel run -c opt @pip_deps_tensorboard//:rules_python_wheel_entry_point_tensorboard -- --logdir %s',
+        FLAGS.workdir,
+    )
+
+    if FLAGS.swerve:
+        physics_constants = jax_dynamics.Coefficients()
+        problem = physics.SwerveProblem(physics_constants)
+    else:
+        problem = physics.TurretProblem()
+
+    state = train.train(FLAGS.workdir, problem)
+
+
+if __name__ == '__main__':
+    flags.mark_flags_as_required(['workdir'])
+    app.run(main)
diff --git a/frc971/control_loops/swerve/velocity_controller/model.py b/frc971/control_loops/swerve/velocity_controller/model.py
new file mode 100644
index 0000000..7f01eef
--- /dev/null
+++ b/frc971/control_loops/swerve/velocity_controller/model.py
@@ -0,0 +1,595 @@
+from __future__ import annotations
+import flax
+import flashbax
+from typing import Any
+import dataclasses
+import absl
+from absl import logging
+import numpy
+import jax
+from flax import linen as nn
+from jaxtyping import Array, ArrayLike
+import optax
+from flax.training import train_state
+from jax.experimental import mesh_utils
+from jax.sharding import Mesh, PartitionSpec, NamedSharding
+from frc971.control_loops.swerve import jax_dynamics
+from frc971.control_loops.swerve.velocity_controller import physics
+from frc971.control_loops.swerve.velocity_controller import experience_buffer
+from tensorflow_probability.substrates import jax as tfp
+
+tfd = tfp.distributions
+tfb = tfp.bijectors
+
+from flax.typing import PRNGKey
+
+FLAGS = absl.flags.FLAGS
+
+absl.flags.DEFINE_integer(
+    'num_agents',
+    default=10,
+    help='Training batch size.',
+)
+
+absl.flags.DEFINE_float(
+    'alpha_learning_rate',
+    default=0.004,
+    help='Training learning rate for entropy.',
+)
+
+absl.flags.DEFINE_float(
+    'q_learning_rate',
+    default=0.002,
+    help='Training learning rate.',
+)
+
+absl.flags.DEFINE_float(
+    'final_q_learning_rate',
+    default=0.001,
+    help='Fraction of --q_learning_rate to reduce by by the end.',
+)
+
+absl.flags.DEFINE_float(
+    'pi_learning_rate',
+    default=0.002,
+    help='Training learning rate.',
+)
+
+absl.flags.DEFINE_float(
+    'final_pi_learning_rate',
+    default=0.001,
+    help='Fraction of --pi_learning_rate to reduce by by the end.',
+)
+
+absl.flags.DEFINE_float(
+    'target_entropy_scalar',
+    default=1.0,
+    help=
+    'Target entropy scalar for use when using automatic temperature adjustment.',
+)
+
+absl.flags.DEFINE_integer(
+    'replay_size',
+    default=2000000,
+    help='Number of steps to save in our replay buffer',
+)
+
+absl.flags.DEFINE_integer(
+    'batch_size',
+    default=10000,
+    help='Batch size for learning Q and pi',
+)
+
+absl.flags.DEFINE_boolean(
+    'skip_layer',
+    default=False,
+    help='If true, add skip layer connections to the Q network.',
+)
+
+absl.flags.DEFINE_boolean(
+    'rmsnorm',
+    default=False,
+    help='If true, use rmsnorm instead of layer norm.',
+)
+
+absl.flags.DEFINE_boolean(
+    'dreamer_solver',
+    default=False,
+    help='If true, use the solver from dreamer v3 instead of adam.',
+)
+
+absl.flags.DEFINE_float(
+    'initial_logalpha',
+    default=0.0,
+    help='The initial value to set logalpha to.',
+)
+
+HIDDEN_WEIGHTS = 256
+
+LOG_STD_MIN = -20
+LOG_STD_MAX = 2
+
+
+def gaussian_likelihood(noise: ArrayLike, log_std: ArrayLike):
+    pre_sum = -0.5 * (noise**2 + 2 * log_std + jax.numpy.log(2 * jax.numpy.pi))
+
+    if len(pre_sum.shape) > 1:
+        return jax.numpy.sum(pre_sum, keepdims=True, axis=1)
+    else:
+        return jax.numpy.sum(pre_sum, keepdims=True)
+
+
+class SquashedGaussianMLPActor(nn.Module):
+    """Actor model."""
+
+    # Number of dimensions in the action space
+    action_space: int = 8
+
+    hidden_sizes: list[int] = dataclasses.field(
+        default_factory=lambda: [HIDDEN_WEIGHTS, HIDDEN_WEIGHTS])
+
+    # Activation function
+    activation: Callable = nn.activation.relu
+
+    # Max action we can apply
+    action_limit: float = 1
+
+    @nn.compact
+    def __call__(self,
+                 observation: ArrayLike,
+                 R: ArrayLike,
+                 deterministic: bool = False,
+                 rng: PRNGKey | None = None):
+        x = jax.numpy.hstack((observation, R))
+        # Apply the dense layers
+        for i, hidden_size in enumerate(self.hidden_sizes):
+            x = nn.Dense(
+                name=f'denselayer{i}',
+                features=hidden_size,
+            )(x)
+            x = self.activation(x)
+
+        # Average policy is a dense function of the space.
+        mu = nn.Dense(
+            features=self.action_space,
+            name='mu',
+        )(x)
+
+        log_std_layer = nn.Dense(features=self.action_space,
+                                 name='log_std_layer')(x)
+
+        # Clip the log of the standard deviation in a soft manner.
+        log_std = LOG_STD_MIN + 0.5 * (LOG_STD_MAX - LOG_STD_MIN) * (
+            flax.linen.activation.tanh(log_std_layer) + 1)
+
+        std = jax.numpy.exp(log_std)
+
+        if rng is None:
+            rng = self.make_rng('pi')
+
+        pi_distribution = tfd.TransformedDistribution(
+            distribution=tfd.Normal(loc=mu, scale=std),
+            bijector=tfb.Tanh(),
+        )
+
+        if deterministic:
+            # We are testing the optimal policy, just use the mean.
+            pi_action = flax.linen.activation.tanh(mu)
+        else:
+            pi_action = pi_distribution.sample(shape=(1, ), seed=rng)
+
+        logp_pi = pi_distribution.log_prob(pi_action)
+
+        if len(logp_pi.shape) > 1:
+            logp_pi = jax.numpy.sum(logp_pi, keepdims=True, axis=1)
+        else:
+            logp_pi = jax.numpy.sum(logp_pi, keepdims=True)
+
+        return pi_action, logp_pi, self.action_limit * std
+
+
+class MLPQFunction(nn.Module):
+
+    # Number and size of the hidden layers.
+    hidden_sizes: list[int] = dataclasses.field(
+        default_factory=lambda: [HIDDEN_WEIGHTS, HIDDEN_WEIGHTS])
+
+    activation: Callable = nn.activation.tanh
+
+    @nn.compact
+    def __call__(self, observation: ArrayLike, R: ArrayLike,
+                 action: ArrayLike):
+        # Estimate Q with a simple multi layer dense network.
+        x = jax.numpy.hstack((observation, R, action))
+        for i, hidden_size in enumerate(self.hidden_sizes):
+            # Add d2rl skip layer connections if requested.
+            # Idea from D2RL: https://arxiv.org/pdf/2010.09163.
+            if FLAGS.skip_layer and i != 0:
+                x = jax.numpy.hstack((x, observation, R, action))
+
+            x = nn.Dense(
+                name=f'denselayer{i}',
+                features=hidden_size,
+            )(x)
+
+            if FLAGS.rmsnorm:
+                # Idea from Dreamerv3: https://arxiv.org/pdf/2301.04104v2.
+                x = nn.RMSNorm(name=f'rmsnorm{i}')(x)
+            else:
+                # Layernorm also improves stability.
+                # Idea from RLPD: https://arxiv.org/pdf/2302.02948.
+                x = nn.LayerNorm(name=f'layernorm{i}')(x)
+            x = self.activation(x)
+
+        x = nn.Dense(
+            name=f'q',
+            features=1,
+        )(x)
+
+        return x
+
+
+class TrainState(flax.struct.PyTreeNode):
+    problem: Problem = flax.struct.field(pytree_node=False)
+
+    step: int | jax.Array = flax.struct.field(pytree_node=True)
+    substep: int | jax.Array = flax.struct.field(pytree_node=True)
+
+    params: flax.core.FrozenDict[str, typing.Any] = flax.struct.field(
+        pytree_node=True)
+
+    target_params: flax.core.FrozenDict[str, typing.Any] = flax.struct.field(
+        pytree_node=True)
+
+    pi_apply_fn: Callable = flax.struct.field(pytree_node=False)
+    q1_apply_fn: Callable = flax.struct.field(pytree_node=False)
+    q2_apply_fn: Callable = flax.struct.field(pytree_node=False)
+
+    pi_tx: optax.GradientTransformation = flax.struct.field(pytree_node=False)
+    pi_opt_state: optax.OptState = flax.struct.field(pytree_node=True)
+    q_tx: optax.GradientTransformation = flax.struct.field(pytree_node=False)
+    q_opt_state: optax.OptState = flax.struct.field(pytree_node=True)
+
+    alpha_tx: optax.GradientTransformation = flax.struct.field(
+        pytree_node=False)
+    alpha_opt_state: optax.OptState = flax.struct.field(pytree_node=True)
+
+    target_entropy: float = flax.struct.field(pytree_node=True)
+
+    mesh: Mesh = flax.struct.field(pytree_node=False)
+    sharding: NamedSharding = flax.struct.field(pytree_node=False)
+    replicated_sharding: NamedSharding = flax.struct.field(pytree_node=False)
+
+    replay_buffer: flashbax.buffers.trajectory_buffer.TrajectoryBuffer = flax.struct.field(
+        pytree_node=False)
+
+    def pi_apply(self,
+                 rng: PRNGKey,
+                 params: flax.core.FrozenDict[str, typing.Any],
+                 observation: ArrayLike,
+                 R: ArrayLike,
+                 deterministic: bool = False):
+        return self.pi_apply_fn(
+            {'params': params['pi']},
+            observation=self.problem.unwrap_angles(observation),
+            R=R,
+            deterministic=deterministic,
+            rngs={'pi': rng})
+
+    def q1_apply(self, params: flax.core.FrozenDict[str, typing.Any],
+                 observation: ArrayLike, R: ArrayLike, action: ArrayLike):
+        return self.q1_apply_fn(
+            {'params': params['q1']},
+            observation=self.problem.unwrap_angles(observation),
+            R=R,
+            action=action)
+
+    def q2_apply(self, params: flax.core.FrozenDict[str, typing.Any],
+                 observation: ArrayLike, R: ArrayLike, action: ArrayLike):
+        return self.q2_apply_fn(
+            {'params': params['q2']},
+            observation=self.problem.unwrap_angles(observation),
+            R=R,
+            action=action)
+
+    def pi_apply_gradients(self, step: int, grads):
+        updates, new_pi_opt_state = self.pi_tx.update(grads, self.pi_opt_state,
+                                                      self.params)
+        new_params = optax.apply_updates(self.params, updates)
+
+        return self.replace(
+            step=step,
+            substep=jax.lax.select(step != self.step, 0, self.substep + 1),
+            params=new_params,
+            pi_opt_state=new_pi_opt_state,
+        )
+
+    def q_apply_gradients(self, step: int, grads):
+        updates, new_q_opt_state = self.q_tx.update(grads, self.q_opt_state,
+                                                    self.params)
+        new_params = optax.apply_updates(self.params, updates)
+
+        return self.replace(
+            step=step,
+            substep=jax.lax.select(step != self.step, 0, self.substep + 1),
+            params=new_params,
+            q_opt_state=new_q_opt_state,
+        )
+
+    def target_apply_gradients(self, step):
+        new_target_params = optax.incremental_update(self.params,
+                                                     self.target_params,
+                                                     1 - FLAGS.polyak)
+
+        return self.replace(
+            step=step,
+            substep=jax.lax.select(step != self.step, 0, self.substep + 1),
+            target_params=new_target_params,
+        )
+
+    def alpha_apply_gradients(self, step, grads):
+        updates, new_alpha_opt_state = self.alpha_tx.update(
+            grads, self.alpha_opt_state, self.params)
+        new_params = optax.apply_updates(self.params, updates)
+
+        return self.replace(
+            step=step,
+            substep=jax.lax.select(step != self.step, 0, self.substep + 1),
+            params=new_params,
+            alpha_opt_state=new_alpha_opt_state,
+        )
+
+    def update_step(self, step):
+        return self.replace(
+            step=step,
+            substep=jax.lax.select(step != self.step, 0, self.substep + 1),
+        )
+
+    @classmethod
+    def create(cls, *, problem: Problem, params, pi_tx, q_tx, alpha_tx,
+               pi_apply_fn, q1_apply_fn, q2_apply_fn, **kwargs):
+        """Creates a new instance with ``step=0`` and initialized ``opt_state``."""
+
+        pi_tx = optax.multi_transform(
+            {
+                'train': pi_tx,
+                'freeze': optax.set_to_zero()
+            },
+            param_labels=flax.traverse_util.path_aware_map(
+                lambda path, x: 'train'
+                if path[0] == 'pi' else 'freeze', params),
+        )
+        pi_opt_state = pi_tx.init(params)
+
+        q_tx = optax.multi_transform(
+            {
+                'train': q_tx,
+                'freeze': optax.set_to_zero()
+            },
+            param_labels=flax.traverse_util.path_aware_map(
+                lambda path, x: 'train'
+                if path[0] == 'q1' or path[0] == 'q2' else 'freeze', params),
+        )
+        q_opt_state = q_tx.init(params)
+
+        alpha_tx = optax.multi_transform(
+            {
+                'train': alpha_tx,
+                'freeze': optax.set_to_zero()
+            },
+            param_labels=flax.traverse_util.path_aware_map(
+                lambda path, x: 'train'
+                if path[0] == 'logalpha' else 'freeze', params),
+        )
+        alpha_opt_state = alpha_tx.init(params)
+
+        mesh = Mesh(
+            devices=mesh_utils.create_device_mesh(len(jax.devices())),
+            axis_names=('batch', ),
+        )
+        print('Devices:', jax.devices())
+        sharding = NamedSharding(mesh, PartitionSpec('batch'))
+        replicated_sharding = NamedSharding(mesh, PartitionSpec())
+
+        replay_buffer = experience_buffer.make_experience_buffer(
+            num_agents=FLAGS.num_agents,
+            sample_batch_size=FLAGS.batch_size,
+            length=FLAGS.replay_size)
+
+        result = cls(
+            problem=problem,
+            step=0,
+            substep=0,
+            params=params,
+            target_params=params,
+            q1_apply_fn=q1_apply_fn,
+            q2_apply_fn=q2_apply_fn,
+            pi_apply_fn=pi_apply_fn,
+            pi_tx=pi_tx,
+            pi_opt_state=pi_opt_state,
+            q_tx=q_tx,
+            q_opt_state=q_opt_state,
+            alpha_tx=alpha_tx,
+            alpha_opt_state=alpha_opt_state,
+            target_entropy=-problem.num_outputs * FLAGS.target_entropy_scalar,
+            mesh=mesh,
+            sharding=sharding,
+            replicated_sharding=replicated_sharding,
+            replay_buffer=replay_buffer,
+        )
+
+        return jax.device_put(result, replicated_sharding)
+
+
+def create_train_state(rng: PRNGKey, problem: Problem, q_learning_rate,
+                       pi_learning_rate, alpha_learning_rate):
+    """Creates initial `TrainState`."""
+    pi = SquashedGaussianMLPActor(activation=nn.activation.silu,
+                                  action_space=problem.num_outputs,
+                                  action_limit=problem.action_limit)
+    # We want q1 and q2 to have different network architectures so they pick up differnet things.
+    # SiLu is used in DreamerV3 so we use it: https://arxiv.org/pdf/2301.04104v2.
+    q1 = MLPQFunction(activation=nn.activation.silu, hidden_sizes=[128, 256])
+    q2 = MLPQFunction(activation=nn.activation.silu, hidden_sizes=[256, 128])
+
+    @jax.jit
+    def init_params(rng):
+        pi_rng, q1_rng, q2_rng = jax.random.split(rng, num=3)
+
+        pi_params = pi.init(
+            pi_rng,
+            observation=jax.numpy.ones([problem.num_unwrapped_states]),
+            R=jax.numpy.ones([problem.num_goals]),
+        )['params']
+        q1_params = q1.init(
+            q1_rng,
+            observation=jax.numpy.ones([problem.num_unwrapped_states]),
+            R=jax.numpy.ones([problem.num_goals]),
+            action=jax.numpy.ones([problem.num_outputs]),
+        )['params']
+        q2_params = q2.init(
+            q2_rng,
+            observation=jax.numpy.ones([problem.num_unwrapped_states]),
+            R=jax.numpy.ones([problem.num_goals]),
+            action=jax.numpy.ones([problem.num_outputs]),
+        )['params']
+
+        if FLAGS.alpha < 0.0:
+            logalpha = FLAGS.initial_logalpha
+        else:
+            logalpha = jax.numpy.log(FLAGS.alpha)
+
+        return {
+            'q1': q1_params,
+            'q2': q2_params,
+            'pi': pi_params,
+            'logalpha': logalpha,
+        }
+
+    if FLAGS.dreamer_solver:
+        pi_tx = create_dreamer_solver(learning_rate=pi_learning_rate)
+        q_tx = create_dreamer_solver(learning_rate=q_learning_rate)
+        alpha_tx = create_dreamer_solver(learning_rate=alpha_learning_rate)
+    else:
+        pi_tx = optax.adam(learning_rate=pi_learning_rate)
+        q_tx = optax.adam(learning_rate=q_learning_rate)
+        alpha_tx = optax.adam(learning_rate=alpha_learning_rate)
+
+    result = TrainState.create(
+        problem=problem,
+        params=init_params(rng),
+        pi_tx=pi_tx,
+        q_tx=q_tx,
+        alpha_tx=alpha_tx,
+        pi_apply_fn=pi.apply,
+        q1_apply_fn=q1.apply,
+        q2_apply_fn=q2.apply,
+    )
+
+    return result
+
+
+# Solver from dreamer v3: https://arxiv.org/pdf/2301.04104v2.
+# TODO(austin): How many of these pieces are actually in optax already?
+def scale_by_rms(beta=0.999, eps=1e-8):
+
+    def init_fn(params):
+        nu = jax.tree_util.tree_map(
+            lambda t: jax.numpy.zeros_like(t, jax.numpy.float32), params)
+        step = jax.numpy.zeros((), jax.numpy.int32)
+        return (step, nu)
+
+    def update_fn(updates, state, params=None):
+        step, nu = state
+        step = optax.safe_int32_increment(step)
+        nu = jax.tree_util.tree_map(
+            lambda v, u: beta * v + (1 - beta) * (u * u), nu, updates)
+        nu_hat = optax.bias_correction(nu, beta, step)
+        updates = jax.tree_util.tree_map(
+            lambda u, v: u / (jax.numpy.sqrt(v) + eps), updates, nu_hat)
+        return updates, (step, nu)
+
+    return optax.GradientTransformation(init_fn, update_fn)
+
+
+def scale_by_agc(clip=0.03, pmin=1e-3):
+
+    def init_fn(params):
+        return ()
+
+    def update_fn(updates, state, params=None):
+
+        def fn(param, update):
+            unorm = jax.numpy.linalg.norm(update.flatten(), 2)
+            pnorm = jax.numpy.linalg.norm(param.flatten(), 2)
+            upper = clip * jax.numpy.maximum(pmin, pnorm)
+            return update * (1 / jax.numpy.maximum(1.0, unorm / upper))
+
+        updates = jax.tree_util.tree_map(fn, params, updates)
+        return updates, ()
+
+    return optax.GradientTransformation(init_fn, update_fn)
+
+
+def scale_by_momentum(beta=0.9, nesterov=False):
+
+    def init_fn(params):
+        mu = jax.tree_util.tree_map(
+            lambda t: jax.numpy.zeros_like(t, jax.numpy.float32), params)
+        step = jax.numpy.zeros((), jax.numpy.int32)
+        return (step, mu)
+
+    def update_fn(updates, state, params=None):
+        step, mu = state
+        step = optax.safe_int32_increment(step)
+        mu = optax.update_moment(updates, mu, beta, 1)
+        if nesterov:
+            mu_nesterov = optax.update_moment(updates, mu, beta, 1)
+            mu_hat = optax.bias_correction(mu_nesterov, beta, step)
+        else:
+            mu_hat = optax.bias_correction(mu, beta, step)
+        return mu_hat, (step, mu)
+
+    return optax.GradientTransformation(init_fn, update_fn)
+
+
+def create_dreamer_solver(
+    learning_rate,
+    agc: float = 0.3,
+    pmin: float = 1e-3,
+    beta1: float = 0.9,
+    beta2: float = 0.999,
+    eps: float = 1e-20,
+    nesterov: bool = False,
+) -> optax.base.GradientTransformation:
+    # From dreamer v3.
+    return optax.chain(
+        # Adaptive gradient clipping.
+        scale_by_agc(agc, pmin),
+        scale_by_rms(beta2, eps),
+        scale_by_momentum(beta1, nesterov),
+        optax.scale_by_learning_rate(learning_rate),
+    )
+
+
+def create_learning_rate_fn(
+    base_learning_rate: float,
+    final_learning_rate: float,
+):
+    """Create learning rate schedule."""
+    warmup_fn = optax.linear_schedule(
+        init_value=base_learning_rate,
+        end_value=base_learning_rate,
+        transition_steps=FLAGS.warmup_steps,
+    )
+
+    cosine_epochs = max(FLAGS.steps - FLAGS.warmup_steps, 1)
+    cosine_fn = optax.cosine_decay_schedule(init_value=base_learning_rate,
+                                            decay_steps=cosine_epochs,
+                                            alpha=final_learning_rate)
+
+    schedule_fn = optax.join_schedules(
+        schedules=[warmup_fn, cosine_fn],
+        boundaries=[FLAGS.warmup_steps],
+    )
+    return schedule_fn
diff --git a/frc971/control_loops/swerve/velocity_controller/physics.py b/frc971/control_loops/swerve/velocity_controller/physics.py
new file mode 100644
index 0000000..accd0d6
--- /dev/null
+++ b/frc971/control_loops/swerve/velocity_controller/physics.py
@@ -0,0 +1,247 @@
+import jax, numpy
+from functools import partial
+from absl import logging
+from frc971.control_loops.swerve import jax_dynamics
+from frc971.control_loops.python import controls
+from flax.typing import PRNGKey
+
+
+class Problem(object):
+
+    def __init__(self, num_states: int, num_unwrapped_states: int,
+                 num_outputs: int, num_goals: int, action_limit: float):
+        self.num_states = num_states
+        self.num_unwrapped_states = num_unwrapped_states
+        self.num_outputs = num_outputs
+        self.num_goals = num_goals
+        self.action_limit = action_limit
+        self.dt = 0.005
+
+    def integrate_dynamics(self, X: jax.typing.ArrayLike,
+                           U: jax.typing.ArrayLike):
+        m = 2  # RK4 steps per interval
+        dt = self.dt / m
+
+        def iteration(i, X):
+            weights = jax.numpy.array([[0.0, 0.5, 0.5, 1.0],
+                                       [1.0, 2.0, 2.0, 1.0]])
+
+            def rk_iteration(i, val):
+                kx_previous, weighted_sum = val
+                kx = self.xdot(X + dt * weights[0, i] * kx_previous, U)
+                weighted_sum += dt * weights[1, i] * kx / 6.0
+                return (kx, weighted_sum)
+
+            return jax.lax.fori_loop(lower=0,
+                                     upper=4,
+                                     body_fun=rk_iteration,
+                                     init_val=(X, X))[1]
+
+        return jax.lax.fori_loop(lower=0,
+                                 upper=m,
+                                 body_fun=iteration,
+                                 init_val=X)
+
+    def unwrap_angles(self, X: jax.typing.ArrayLike):
+        return X
+
+    def xdot(self, X: jax.typing.ArrayLike, U: jax.typing.ArrayLike):
+        raise NotImplemented("xdot not implemented")
+
+    def cost(self, X: jax.typing.ArrayLike, U: jax.typing.ArrayLike,
+             goal: jax.typing.ArrayLike):
+        raise NotImplemented("cost not implemented")
+
+    def random_states(self, rng: PRNGKey, dimensions=None):
+        raise NotImplemented("random_states not implemented")
+
+    def random_actions(self,
+                       rng: PRNGKey,
+                       X: jax.typing.ArrayLike,
+                       goal: jax.typing.ArrayLike,
+                       dimensions=None):
+        """Produces a uniformly random action in the action space."""
+        return jax.random.uniform(
+            rng,
+            (dimensions or FLAGS.num_agents, self.num_outputs),
+            minval=-1.0,
+            maxval=1.0,
+        )
+
+    def random_goals(self, rng: PRNGKey, dimensions=None):
+        """Produces a random goal in the goal space."""
+        raise NotImplemented("random_states not implemented")
+
+
+class TurretProblem(Problem):
+
+    def __init__(self):
+        super().__init__(num_states=2,
+                         num_unwrapped_states=2,
+                         num_outputs=1,
+                         num_goals=2,
+                         action_limit=30.0)
+        self.A = numpy.matrix([[1., 0.00456639], [0., 0.83172142]])
+        self.B = numpy.matrix([[0.00065992], [0.25610763]])
+
+        self.Q = numpy.matrix([[2.77777778, 0.], [0., 0.01]])
+        self.R = numpy.matrix([[0.00694444]])
+
+        # Compute the optimal LQR cost + controller.
+        self.F, self.P = controls.dlqr(self.A,
+                                       self.B,
+                                       self.Q,
+                                       self.R,
+                                       optimal_cost_function=True)
+
+    def xdot(self, X: jax.typing.ArrayLike, U: jax.typing.ArrayLike):
+        A_continuous = jax.numpy.array([[0., 1.], [0., -36.85154548]])
+        B_continuous = jax.numpy.array([[0.], [56.08534375]])
+
+        U = U * self.action_limit
+        return A_continuous @ X + B_continuous @ U
+
+    def reward(self, X: jax.typing.ArrayLike, U: jax.typing.ArrayLike,
+               goal: jax.typing.ArrayLike):
+        return -(X - goal).T @ jax.numpy.array(
+            self.Q) @ (X - goal) - U.T @ jax.numpy.array(self.R) @ U
+
+    def random_states(self, rng: PRNGKey, dimensions=None):
+        rng1, rng2 = jax.random.split(rng)
+
+        return jax.numpy.hstack(
+            (jax.random.uniform(rng1, (dimensions or FLAGS.num_agents, 1),
+                                minval=-1.0,
+                                maxval=1.0),
+             jax.random.uniform(rng2, (dimensions or FLAGS.num_agents, 1),
+                                minval=-10.0,
+                                maxval=10.0)))
+
+    def random_goals(self, rng: PRNGKey, dimensions=None):
+        """Produces a random goal in the goal space."""
+        return jax.numpy.hstack((
+            jax.random.uniform(rng, (dimensions or FLAGS.num_agents, 1),
+                               minval=-0.1,
+                               maxval=0.1),
+            jax.numpy.zeros((dimensions or FLAGS.num_agents, 1)),
+        ))
+
+
+class SwerveProblem(Problem):
+
+    def __init__(self, coefficients: jax_dynamics.CoefficientsType):
+        super().__init__(num_states=jax_dynamics.NUM_VELOCITY_STATES,
+                         num_unwrapped_states=17,
+                         num_outputs=8,
+                         num_goals=3,
+                         action_limit=40.0)
+
+        self.coefficients = coefficients
+
+    def random_actions(self,
+                       rng: PRNGKey,
+                       X: jax.typing.ArrayLike,
+                       goal: jax.typing.ArrayLike,
+                       dimensions=None):
+        """Produces a uniformly random action in the action space."""
+        return jax.random.uniform(
+            rng,
+            (dimensions or FLAGS.num_agents, self.num_outputs),
+            minval=-1.0,
+            maxval=1.0,
+        )
+
+    def unwrap_angles(self, X: jax.typing.ArrayLike):
+        return jax.numpy.stack([
+            jax.numpy.cos(X[..., jax_dynamics.VELOCITY_STATE_THETAS0]),
+            jax.numpy.sin(X[..., jax_dynamics.VELOCITY_STATE_THETAS0]),
+            X[..., jax_dynamics.VELOCITY_STATE_OMEGAS0],
+            jax.numpy.cos(X[..., jax_dynamics.VELOCITY_STATE_THETAS1]),
+            jax.numpy.sin(X[..., jax_dynamics.VELOCITY_STATE_THETAS1]),
+            X[..., jax_dynamics.VELOCITY_STATE_OMEGAS1],
+            jax.numpy.cos(X[..., jax_dynamics.VELOCITY_STATE_THETAS2]),
+            jax.numpy.sin(X[..., jax_dynamics.VELOCITY_STATE_THETAS2]),
+            X[..., jax_dynamics.VELOCITY_STATE_OMEGAS2],
+            jax.numpy.cos(X[..., jax_dynamics.VELOCITY_STATE_THETAS3]),
+            jax.numpy.sin(X[..., jax_dynamics.VELOCITY_STATE_THETAS3]),
+            X[..., jax_dynamics.VELOCITY_STATE_OMEGAS3],
+            jax.numpy.cos(X[..., jax_dynamics.VELOCITY_STATE_THETA]),
+            jax.numpy.sin(X[..., jax_dynamics.VELOCITY_STATE_THETA]),
+            X[..., jax_dynamics.VELOCITY_STATE_VX],
+            X[..., jax_dynamics.VELOCITY_STATE_VY],
+            X[..., jax_dynamics.VELOCITY_STATE_OMEGA],
+        ],
+                               axis=-1)
+
+    def xdot(self, X: jax.typing.ArrayLike, U: jax.typing.ArrayLike):
+        return jax_dynamics.velocity_dynamics(self.coefficients, X,
+                                              self.action_limit * U)
+
+    def reward(self, X: jax.typing.ArrayLike, U: jax.typing.ArrayLike,
+               goal: jax.typing.ArrayLike):
+        return -jax_dynamics.mpc_cost(coefficients=self.coefficients,
+                                      X=X,
+                                      U=self.action_limit * U,
+                                      goal=goal)
+
+    def random_states(self, rng: PRNGKey, dimensions=None):
+        rng, rng1, rng2, rng3, rng4, rng5, rng6, rng7, rng8, rng9, rng10, rng11 = jax.random.split(
+            rng, num=12)
+
+        return jax.numpy.hstack((
+            # VELOCITY_STATE_THETAS0 = 0
+            self._random_angle(rng1, dimensions),
+            # VELOCITY_STATE_OMEGAS0 = 1
+            self._random_module_velocity(rng2, dimensions),
+            # VELOCITY_STATE_THETAS1 = 2
+            self._random_angle(rng3, dimensions),
+            # VELOCITY_STATE_OMEGAS1 = 3
+            self._random_module_velocity(rng4, dimensions),
+            # VELOCITY_STATE_THETAS2 = 4
+            self._random_angle(rng5, dimensions),
+            # VELOCITY_STATE_OMEGAS2 = 5
+            self._random_module_velocity(rng6, dimensions),
+            # VELOCITY_STATE_THETAS3 = 6
+            self._random_angle(rng7, dimensions),
+            # VELOCITY_STATE_OMEGAS3 = 7
+            self._random_module_velocity(rng8, dimensions),
+            # VELOCITY_STATE_THETA = 8
+            self._random_angle(rng9, dimensions),
+            # VELOCITY_STATE_VX = 9
+            # VELOCITY_STATE_VY = 10
+            self._random_robot_velocity(rng10, dimensions),
+            # VELOCITY_STATE_OMEGA = 11
+            self._random_robot_angular_velocity(rng11, dimensions),
+        ))
+
+    def random_goals(self, rng: PRNGKey, dimensions=None):
+        """Produces a random goal in the goal space."""
+        return jax.numpy.hstack((
+            jax.random.uniform(rng, (dimensions or FLAGS.num_agents, 1),
+                               minval=1.0,
+                               maxval=1.0),
+            jax.numpy.zeros((dimensions or FLAGS.num_agents, 2)),
+        ))
+
+    MODULE_VELOCITY = 1.0
+    ROBOT_ANGULAR_VELOCITY = 0.5
+
+    def _random_angle(self, rng: PRNGKey, dimensions=None):
+        return jax.random.uniform(rng, (dimensions or FLAGS.num_agents, 1),
+                                  minval=-0.1 * jax.numpy.pi,
+                                  maxval=0.1 * jax.numpy.pi)
+
+    def _random_module_velocity(self, rng: PRNGKey, dimensions=None):
+        return jax.random.uniform(rng, (dimensions or FLAGS.num_agents, 1),
+                                  minval=-self.MODULE_VELOCITY,
+                                  maxval=self.MODULE_VELOCITY)
+
+    def _random_robot_velocity(self, rng: PRNGKey, dimensions=None):
+        return jax.random.uniform(rng, (dimensions or FLAGS.num_agents, 2),
+                                  minval=0.9,
+                                  maxval=1.1)
+
+    def _random_robot_angular_velocity(self, rng: PRNGKey, dimensions=None):
+        return jax.random.uniform(rng, (dimensions or FLAGS.num_agents, 1),
+                                  minval=-self.ROBOT_ANGULAR_VELOCITY,
+                                  maxval=self.ROBOT_ANGULAR_VELOCITY)
diff --git a/frc971/control_loops/swerve/velocity_controller/plot.py b/frc971/control_loops/swerve/velocity_controller/plot.py
new file mode 100644
index 0000000..502a3e2
--- /dev/null
+++ b/frc971/control_loops/swerve/velocity_controller/plot.py
@@ -0,0 +1,430 @@
+#!/usr/bin/env python3
+
+import os
+
+os.environ['XLA_FLAGS'] = ' '.join([
+    # Teach it where to find CUDA
+    '--xla_gpu_cuda_data_dir=/usr/lib/cuda',
+    # Use up to 20 cores
+    '--xla_force_host_platform_device_count=20',
+    # Dump XLA to /tmp/foo to aid debugging
+    #'--xla_dump_to=/tmp/foo',
+    #'--xla_gpu_enable_command_buffer='
+])
+
+os.environ['JAX_PLATFORMS'] = 'cpu'
+# Don't pre-allocate memory
+os.environ['XLA_PYTHON_CLIENT_PREALLOCATE'] = 'false'
+
+import absl
+from absl import logging
+from matplotlib.animation import FuncAnimation
+import matplotlib
+import numpy
+import scipy
+import time
+
+matplotlib.use("gtk3agg")
+
+from matplotlib import pylab
+from matplotlib import pyplot
+from flax.training import checkpoints
+import tensorflow as tf
+from jax.experimental.ode import odeint
+import threading
+import collections
+
+from frc971.control_loops.swerve.velocity_controller.model import *
+from frc971.control_loops.swerve.velocity_controller.physics import *
+
+# Container for the data.
+Data = collections.namedtuple('Data', [
+    't', 'X', 'U', 'logp_pi', 'cost', 'q1_grid', 'q2_grid', 'q_grid',
+    'target_q_grid', 'pi_grid_U', 'grid_X', 'grid_Y', 'reward', 'step',
+    'rewards'
+])
+
+FLAGS = absl.flags.FLAGS
+
+absl.flags.DEFINE_string('workdir', None, 'Directory to store model data.')
+
+absl.flags.DEFINE_integer(
+    'horizon',
+    default=100,
+    help='MPC horizon',
+)
+
+numpy.set_printoptions(linewidth=200, )
+
+absl.flags.DEFINE_float(
+    'alpha',
+    default=0.2,
+    help='Entropy.  If negative, automatically solve for it.',
+)
+
+
+def restore_checkpoint(state: TrainState, workdir: str):
+    return checkpoints.restore_checkpoint(workdir, state)
+
+
+dt = 0.005
+
+
+def X0Full():
+    module_theta = 0.0
+    module_omega = 0.0
+    theta = 0.0
+    vx = 1.0
+    dtheta = 0.05
+    vy = 0.0
+    drive_omega = jax.numpy.hypot(vx, vy) / jax_dynamics.WHEEL_RADIUS
+    omega = 0.0
+    return jax.numpy.array([
+        module_theta + dtheta,
+        0.0,
+        module_omega,
+        drive_omega,
+        module_theta + dtheta,
+        0.0,
+        module_omega,
+        drive_omega,
+        module_theta - dtheta,
+        0.0,
+        module_omega,
+        drive_omega,
+        module_theta - dtheta,
+        0.0,
+        module_omega,
+        drive_omega,
+        0.0,
+        0.0,
+        theta,
+        vx,
+        vy,
+        omega,
+        0.0,
+        0.0,
+        0.0,
+    ])
+
+
+def generate_data(step=None):
+    grid_X = numpy.arange(-1, 1, 0.1)
+    grid_Y = numpy.arange(-10, 10, 0.1)
+    grid_X, grid_Y = numpy.meshgrid(grid_X, grid_Y)
+    grid_X = jax.numpy.array(grid_X)
+    grid_Y = jax.numpy.array(grid_Y)
+    # Load the training state.
+    physics_constants = jax_dynamics.Coefficients()
+    problem = physics.SwerveProblem(physics_constants)
+
+    rng = jax.random.key(0)
+    rng, init_rng = jax.random.split(rng)
+
+    state = create_train_state(init_rng,
+                               problem,
+                               FLAGS.q_learning_rate,
+                               FLAGS.pi_learning_rate,
+                               alpha_learning_rate=0.001)
+
+    state = restore_checkpoint(state, FLAGS.workdir)
+
+    X = X0Full()
+    X_lqr = X.copy()
+    goal = jax.numpy.array([1.0, 0.0, 0.0])
+
+    logging.info('X: %s', X)
+    logging.info('goal: %s', goal)
+    logging.debug('params: %s', state.params)
+
+    # Now simulate the robot, accumulating up things to plot.
+    def loop(i, val):
+        X, data, params = val
+        t = data.t.at[i].set(i * problem.dt)
+
+        U, logp_pi, std = state.pi_apply(
+            rng,
+            params,
+            observation=state.problem.unwrap_angles(
+                jax_dynamics.to_velocity_state(X)),
+            R=goal,
+            deterministic=True)
+
+        logp_pi = logp_pi * jax.numpy.exp(params['logalpha'])
+
+        jax.debug.print('mu: {mu} std: {std}', mu=U, std=std)
+
+        step_reward = state.problem.q_reward(jax_dynamics.to_velocity_state(X),
+                                             U, goal)
+        reward = data.reward + step_reward
+
+        cost = jax.numpy.minimum(
+            state.q1_apply(params,
+                           observation=state.problem.unwrap_angles(
+                               jax_dynamics.to_velocity_state(X)),
+                           R=goal,
+                           action=U),
+            state.q2_apply(params,
+                           observation=state.problem.unwrap_angles(
+                               jax_dynamics.to_velocity_state(X)),
+                           R=goal,
+                           action=U))
+
+        U = U * problem.action_limit
+        U_plot = data.U.at[i, :].set(U)
+        rewards = data.rewards.at[i, :].set(step_reward)
+        X_plot = data.X.at[i, :].set(X)
+        cost_plot = data.cost.at[i, :].set(cost)
+        logp_pi_plot = data.logp_pi.at[i, :].set(logp_pi)
+
+        # TODO(austin): I'd really like to visualize the slip angle per wheel.
+        # Maybe also the force deviation, etc.
+        # I think that would help enormously in figuring out how good a specific solution is.
+
+        def fn(X, t):
+            return jax_dynamics.full_dynamics(problem.coefficients, X,
+                                              U).flatten()
+
+        X = odeint(fn, X, jax.numpy.array([0, problem.dt]))
+
+        return X[1, :], data._replace(
+            t=t,
+            U=U_plot,
+            X=X_plot,
+            logp_pi=logp_pi_plot,
+            cost=cost_plot,
+            reward=reward,
+            rewards=rewards,
+        ), params
+
+    # Do it.
+    @jax.jit
+    def integrate(data, X, params):
+        return jax.lax.fori_loop(0, FLAGS.horizon, loop, (X, data, params))
+
+    X, data, params = integrate(
+        Data(
+            t=jax.numpy.zeros((FLAGS.horizon, )),
+            X=jax.numpy.zeros((FLAGS.horizon, jax_dynamics.NUM_STATES)),
+            U=jax.numpy.zeros((FLAGS.horizon, state.problem.num_outputs)),
+            logp_pi=jax.numpy.zeros((FLAGS.horizon, 1)),
+            rewards=jax.numpy.zeros((FLAGS.horizon, 1)),
+            cost=jax.numpy.zeros((FLAGS.horizon, 1)),
+            q1_grid=jax.numpy.zeros(grid_X.shape),
+            q2_grid=jax.numpy.zeros(grid_X.shape),
+            q_grid=jax.numpy.zeros(grid_X.shape),
+            target_q_grid=jax.numpy.zeros(grid_X.shape),
+            pi_grid_U=jax.numpy.zeros(grid_X.shape),
+            grid_X=grid_X,
+            grid_Y=grid_Y,
+            reward=0.0,
+            step=state.step,
+        ), X, state.params)
+
+    logging.info('Reward: %s', float(data.reward))
+
+    # Convert back to numpy for plotting.
+    return Data(
+        t=numpy.array(data.t),
+        X=numpy.array(data.X),
+        U=numpy.array(data.U),
+        logp_pi=numpy.array(data.logp_pi),
+        cost=numpy.array(data.cost),
+        q1_grid=numpy.array(data.q1_grid),
+        q2_grid=numpy.array(data.q2_grid),
+        q_grid=numpy.array(data.q_grid),
+        target_q_grid=numpy.array(data.target_q_grid),
+        pi_grid_U=numpy.array(data.pi_grid_U),
+        grid_X=numpy.array(data.grid_X),
+        grid_Y=numpy.array(data.grid_Y),
+        rewards=numpy.array(data.rewards),
+        reward=float(data.reward),
+        step=data.step,
+    )
+
+
+class Plotter(object):
+
+    def __init__(self, data):
+        # Make all the plots and axis.
+        self.fig0, self.axs0 = pylab.subplots(3)
+        self.fig0.supxlabel('Seconds')
+
+        self.vx, = self.axs0[0].plot([], [], label="vx")
+        self.vy, = self.axs0[0].plot([], [], label="vy")
+        self.omega, = self.axs0[0].plot([], [], label="omega")
+        self.axs0[0].set_ylabel('Velocity')
+        self.axs0[0].legend()
+        self.axs0[0].grid()
+
+        self.steer0, = self.axs0[1].plot([], [], label="Steer0")
+        self.steer1, = self.axs0[1].plot([], [], label="Steer1")
+        self.steer2, = self.axs0[1].plot([], [], label="Steer2")
+        self.steer3, = self.axs0[1].plot([], [], label="Steer3")
+        self.axs0[1].set_ylabel('Amps')
+        self.axs0[1].legend()
+        self.axs0[1].grid()
+
+        self.drive0, = self.axs0[2].plot([], [], label="Drive0")
+        self.drive1, = self.axs0[2].plot([], [], label="Drive1")
+        self.drive2, = self.axs0[2].plot([], [], label="Drive2")
+        self.drive3, = self.axs0[2].plot([], [], label="Drive3")
+        self.axs0[2].set_ylabel('Amps')
+        self.axs0[2].legend()
+        self.axs0[2].grid()
+
+        self.fig1, self.axs1 = pylab.subplots(3)
+        self.fig1.supxlabel('Seconds')
+
+        self.theta0, = self.axs1[0].plot([], [], label='steer position0')
+        self.theta1, = self.axs1[0].plot([], [], label='steer position1')
+        self.theta2, = self.axs1[0].plot([], [], label='steer position2')
+        self.theta3, = self.axs1[0].plot([], [], label='steer position3')
+        self.axs1[0].set_ylabel('Radians')
+        self.axs1[0].legend()
+        self.omega0, = self.axs1[1].plot([], [], label='steer velocity0')
+        self.omega1, = self.axs1[1].plot([], [], label='steer velocity1')
+        self.omega2, = self.axs1[1].plot([], [], label='steer velocity2')
+        self.omega3, = self.axs1[1].plot([], [], label='steer velocity3')
+        self.axs1[1].set_ylabel('Radians/second')
+        self.axs1[1].legend()
+
+        self.logp_axis = self.axs1[2].twinx()
+        self.cost, = self.axs1[2].plot([], [], label='cost')
+        self.reward, = self.axs1[2].plot([], [], label='reward')
+        self.axs1[2].set_ylabel('Radians/second')
+        self.axs1[2].legend()
+
+        self.logp_pi, = self.logp_axis.plot([], [],
+                                            label='logp_pi',
+                                            color='C2')
+        self.logp_axis.set_ylabel('log(liklihood)*alpha')
+        self.logp_axis.legend()
+
+        self.last_robot_step = 0
+        self.last_steer_step = 0
+
+    def update_robot_plot(self, data):
+        if data.step is not None and data.step == self.last_robot_step:
+            return
+        self.last_robot_step = data.step
+        logging.info('Updating robot plots')
+        self.fig0.suptitle(f'Step {data.step}')
+
+        self.vx.set_data(data.t, data.X[:, jax_dynamics.STATE_VX])
+        self.vy.set_data(data.t, data.X[:, jax_dynamics.STATE_VY])
+        self.omega.set_data(data.t, data.X[:, jax_dynamics.STATE_OMEGA])
+
+        self.axs0[0].relim()
+        self.axs0[0].autoscale_view()
+
+        self.steer0.set_data(data.t, data.U[:, 0])
+        self.steer1.set_data(data.t, data.U[:, 2])
+        self.steer2.set_data(data.t, data.U[:, 4])
+        self.steer3.set_data(data.t, data.U[:, 6])
+        self.axs0[1].relim()
+        self.axs0[1].autoscale_view()
+
+        self.drive0.set_data(data.t, data.U[:, 1])
+        self.drive1.set_data(data.t, data.U[:, 3])
+        self.drive2.set_data(data.t, data.U[:, 5])
+        self.drive3.set_data(data.t, data.U[:, 7])
+        self.axs0[2].relim()
+        self.axs0[2].autoscale_view()
+
+        return (self.vx, self.vy, self.omega, self.steer0, self.steer1,
+                self.steer2, self.steer3, self.drive0, self.drive1,
+                self.drive2, self.drive3)
+
+    def update_steer_plot(self, data):
+        if data.step == self.last_steer_step:
+            return
+        self.last_steer_step = data.step
+        logging.info('Updating steer plots')
+        self.fig1.suptitle(f'Step {data.step}')
+
+        self.theta0.set_data(data.t, data.X[:, jax_dynamics.STATE_THETAS0])
+        self.theta1.set_data(data.t, data.X[:, jax_dynamics.STATE_THETAS1])
+        self.theta2.set_data(data.t, data.X[:, jax_dynamics.STATE_THETAS2])
+        self.theta3.set_data(data.t, data.X[:, jax_dynamics.STATE_THETAS3])
+        self.axs1[0].relim()
+        self.axs1[0].autoscale_view()
+
+        self.omega0.set_data(data.t, data.X[:, jax_dynamics.STATE_OMEGAS0])
+        self.omega1.set_data(data.t, data.X[:, jax_dynamics.STATE_OMEGAS1])
+        self.omega2.set_data(data.t, data.X[:, jax_dynamics.STATE_OMEGAS2])
+        self.omega3.set_data(data.t, data.X[:, jax_dynamics.STATE_OMEGAS3])
+        self.axs1[1].relim()
+        self.axs1[1].autoscale_view()
+
+        self.cost.set_data(data.t, data.cost)
+        self.reward.set_data(data.t, data.rewards)
+        self.logp_pi.set_data(data.t, data.logp_pi)
+        self.axs1[2].relim()
+        self.axs1[2].autoscale_view()
+        self.logp_axis.relim()
+        self.logp_axis.autoscale_view()
+
+        return (self.theta0, self.theta1, self.theta2, self.theta3,
+                self.omega0, self.omega1, self.omega2, self.omega3, self.cost,
+                self.logp_pi, self.reward)
+
+
+def main(argv):
+    if len(argv) > 1:
+        raise absl.app.UsageError('Too many command-line arguments.')
+
+    tf.config.experimental.set_visible_devices([], 'GPU')
+
+    lock = threading.Lock()
+
+    # Load data.
+    data = generate_data()
+
+    plotter = Plotter(data)
+
+    # Event for shutting down the thread.
+    shutdown = threading.Event()
+
+    # Thread to grab new data periodically.
+    def do_update():
+        while True:
+            nonlocal data
+
+            my_data = generate_data(data.step)
+
+            if my_data is not None:
+                with lock:
+                    data = my_data
+
+            if shutdown.wait(timeout=3):
+                return
+
+    update_thread = threading.Thread(target=do_update)
+    update_thread.start()
+
+    # Now, update each of the plots every second with the new data.
+    def update0(frame):
+        with lock:
+            my_data = data
+
+        return plotter.update_robot_plot(my_data)
+
+    def update1(frame):
+        with lock:
+            my_data = data
+
+        return plotter.update_steer_plot(my_data)
+
+    animation0 = FuncAnimation(plotter.fig0, update0, interval=1000)
+    animation1 = FuncAnimation(plotter.fig1, update1, interval=1000)
+
+    pyplot.show()
+
+    shutdown.set()
+    update_thread.join()
+
+
+if __name__ == '__main__':
+    absl.flags.mark_flags_as_required(['workdir'])
+    absl.app.run(main)
diff --git a/frc971/control_loops/swerve/velocity_controller/train.py b/frc971/control_loops/swerve/velocity_controller/train.py
new file mode 100644
index 0000000..34d904a
--- /dev/null
+++ b/frc971/control_loops/swerve/velocity_controller/train.py
@@ -0,0 +1,517 @@
+# Machine learning based on Soft Actor Critic(SAC) which was initially proposed in https://arxiv.org/pdf/1801.01290.
+# Our implementation was heavily based on OpenAI's spinning up reference implementation https://spinningup.openai.com/en/latest/algorithms/sac.html.
+
+import absl
+import time
+import collections
+from absl import logging
+import flax
+import matplotlib
+from matplotlib import pyplot
+from flax import linen as nn
+from flax.training import train_state
+from flax.training import checkpoints
+import jax
+import inspect
+import aim
+import jax.numpy as jnp
+import ml_collections
+import numpy as np
+import optax
+import numpy
+from frc971.control_loops.swerve import jax_dynamics
+from functools import partial
+import flashbax
+from jax.experimental.ode import odeint
+import orbax.checkpoint
+from frc971.control_loops.swerve.velocity_controller.model import *
+from frc971.control_loops.swerve.velocity_controller.physics import *
+
+numpy.set_printoptions(linewidth=200, )
+
+FLAGS = absl.flags.FLAGS
+
+absl.flags.DEFINE_integer(
+    'horizon',
+    default=25,
+    help='MPC horizon',
+)
+
+absl.flags.DEFINE_integer(
+    'random_sample_steps',
+    default=10000,
+    help='Number of steps to randomly sample before using the policy',
+)
+
+absl.flags.DEFINE_integer(
+    'steps',
+    default=400000,
+    help='Number of steps to run and train the agent',
+)
+
+absl.flags.DEFINE_integer(
+    'warmup_steps',
+    default=300000,
+    help='Number of steps to warm up training',
+)
+
+absl.flags.DEFINE_float(
+    'gamma',
+    default=0.999,
+    help='Future discount.',
+)
+
+absl.flags.DEFINE_float(
+    'alpha',
+    default=0.2,
+    help='Entropy.  If negative, automatically solve for it.',
+)
+
+absl.flags.DEFINE_float(
+    'polyak',
+    default=0.995,
+    help='Time constant in polyak averaging for the target network.',
+)
+
+absl.flags.DEFINE_bool(
+    'debug_nan',
+    default=False,
+    help='If true, explode on any NaNs found, and print them.',
+)
+
+absl.flags.DEFINE_bool(
+    'maximum_entropy_q',
+    default=True,
+    help=
+    'If false, do not add the maximum entropy term to the bellman backup for Q.',
+)
+
+
+def save_checkpoint(state: TrainState, workdir: str):
+    """Saves a checkpoint in the workdir."""
+    # TODO(austin): use orbax directly.
+    step = int(state.step)
+    logging.info('Saving checkpoint step %d.', step)
+    checkpoints.save_checkpoint_multiprocess(workdir, state, step, keep=10)
+
+
+def restore_checkpoint(state: TrainState, workdir: str):
+    """Restores the latest checkpoint from the workdir."""
+    return checkpoints.restore_checkpoint(workdir, state)
+
+
+def has_nan(x):
+    if isinstance(x, jnp.ndarray):
+        return jnp.any(jnp.isnan(x))
+    else:
+        return jnp.any(
+            jax.numpy.array([has_nan(v)
+                             for v in jax.tree_util.tree_leaves(x)]))
+
+
+def print_nan(step, x):
+    if not FLAGS.debug_nan:
+        return
+
+    caller = inspect.getframeinfo(inspect.stack()[1][0])
+    # TODO(austin): It is helpful to sometimes start printing at a certain step.
+    jax.lax.cond(
+        has_nan(x), lambda: jax.debug.print(caller.filename +
+                                            ':{l} step {s} isnan(X) -> {x}',
+                                            l=caller.lineno,
+                                            s=step,
+                                            x=x), lambda: None)
+
+
+@jax.jit
+def compute_loss_q(state: TrainState, rng: PRNGKey, params, data: ArrayLike):
+    """Computes the Soft Actor-Critic loss for Q1 and Q2."""
+    observations1 = data['observations1']
+    actions = data['actions']
+    rewards = data['rewards']
+    observations2 = data['observations2']
+    R = data['goals']
+
+    # Compute the ending actions from the current network.
+    action2, logp_pi2, _ = state.pi_apply(rng=rng,
+                                          params=params,
+                                          observation=observations2,
+                                          R=R)
+
+    # Compute target network Q values
+    q1_pi_target = state.q1_apply(state.target_params,
+                                  observation=observations2,
+                                  R=R,
+                                  action=action2)
+    q2_pi_target = state.q2_apply(state.target_params,
+                                  observation=observations2,
+                                  R=R,
+                                  action=action2)
+    q_pi_target = jax.numpy.minimum(q1_pi_target, q2_pi_target)
+
+    alpha = jax.numpy.exp(params['logalpha'])
+
+    # Now we can compute the Bellman backup
+    # Max entropy SAC is based on https://arxiv.org/pdf/1812.05905.
+    if FLAGS.maximum_entropy_q:
+        bellman_backup = jax.lax.stop_gradient(
+            rewards + FLAGS.gamma * (q_pi_target - alpha * logp_pi2))
+    else:
+        bellman_backup = jax.lax.stop_gradient(rewards +
+                                               FLAGS.gamma * q_pi_target)
+
+    # Compute the starting Q values from the Q network being optimized.
+    q1 = state.q1_apply(params, observation=observations1, R=R, action=actions)
+    q2 = state.q2_apply(params, observation=observations1, R=R, action=actions)
+
+    # Mean squared error loss against Bellman backup
+    q1_loss = ((q1 - bellman_backup)**2).mean()
+    q2_loss = ((q2 - bellman_backup)**2).mean()
+    return q1_loss + q2_loss
+
+
+@jax.jit
+def compute_loss_pi(state: TrainState, rng: PRNGKey, params, data: ArrayLike):
+    """Computes the Soft Actor-Critic loss for pi."""
+    observations1 = data['observations1']
+    R = data['goals']
+    # TODO(austin): We've got differentiable policy and differentiable physics.  Can we use those here?  Have Q learn the future, not the current step?
+
+    # Compute the action
+    pi, logp_pi, _ = state.pi_apply(rng=rng,
+                                    params=params,
+                                    observation=observations1,
+                                    R=R)
+    q1_pi = state.q1_apply(jax.lax.stop_gradient(params),
+                           observation=observations1,
+                           R=R,
+                           action=pi)
+    q2_pi = state.q2_apply(jax.lax.stop_gradient(params),
+                           observation=observations1,
+                           R=R,
+                           action=pi)
+
+    # And compute the Q of that action.
+    q_pi = jax.numpy.minimum(q1_pi, q2_pi)
+
+    alpha = jax.lax.stop_gradient(jax.numpy.exp(params['logalpha']))
+
+    # Compute the entropy-regularized policy loss
+    return (alpha * logp_pi - q_pi).mean()
+
+
+@jax.jit
+def compute_loss_alpha(state: TrainState, rng: PRNGKey, params,
+                       data: ArrayLike):
+    """Computes the Soft Actor-Critic loss for alpha."""
+    observations1 = data['observations1']
+    R = data['goals']
+    pi, logp_pi, _ = jax.lax.stop_gradient(
+        state.pi_apply(rng=rng, params=params, observation=observations1, R=R))
+
+    return (-jax.numpy.exp(params['logalpha']) *
+            (logp_pi + state.target_entropy)).mean(), logp_pi.mean()
+
+
+@jax.jit
+def compute_batched_loss_q(state: TrainState, rng: PRNGKey, params,
+                           data: ArrayLike):
+
+    def bound_compute_loss_q(rng, data):
+        return compute_loss_q(state, rng, params, data)
+
+    return jax.vmap(bound_compute_loss_q)(
+        jax.random.split(rng, FLAGS.num_agents),
+        data,
+    ).mean()
+
+
+@jax.jit
+def compute_batched_loss_pi(state: TrainState, rng: PRNGKey, params,
+                            data: ArrayLike):
+
+    def bound_compute_loss_pi(rng, data):
+        return compute_loss_pi(state, rng, params, data)
+
+    return jax.vmap(bound_compute_loss_pi)(
+        jax.random.split(rng, FLAGS.num_agents),
+        data,
+    ).mean()
+
+
+@jax.jit
+def compute_batched_loss_alpha(state: TrainState, rng: PRNGKey, params,
+                               data: ArrayLike):
+
+    def bound_compute_loss_alpha(rng, data):
+        return compute_loss_alpha(state, rng, params, data)
+
+    loss, entropy = jax.vmap(bound_compute_loss_alpha)(
+        jax.random.split(rng, FLAGS.num_agents),
+        data,
+    )
+    return (loss.mean(), entropy.mean())
+
+
+@jax.jit
+def train_step(state: TrainState, data, update_rng: PRNGKey,
+               step: int) -> TrainState:
+    """Updates the parameters for Q, Pi, target Q, and alpha."""
+    update_rng, q_grad_rng = jax.random.split(update_rng)
+    print_nan(step, data)
+
+    # Update Q
+    q_grad_fn = jax.value_and_grad(
+        lambda params: compute_batched_loss_q(state, q_grad_rng, params, data))
+    q_loss, q_grads = q_grad_fn(state.params)
+    print_nan(step, q_loss)
+    print_nan(step, q_grads)
+
+    state = state.q_apply_gradients(step=step, grads=q_grads)
+
+    # Update pi
+    update_rng, pi_grad_rng = jax.random.split(update_rng)
+    pi_grad_fn = jax.value_and_grad(lambda params: compute_batched_loss_pi(
+        state, pi_grad_rng, params, data))
+    pi_loss, pi_grads = pi_grad_fn(state.params)
+    state = state.pi_apply_gradients(step=step, grads=pi_grads)
+
+    update_rng, alpha_grad_rng = jax.random.split(update_rng)
+
+    if FLAGS.alpha < 0.0:
+        # Update alpha
+        alpha_grad_fn = jax.value_and_grad(
+            lambda params: compute_batched_loss_alpha(state, alpha_grad_rng,
+                                                      params, data),
+            has_aux=True,
+        )
+        (alpha_loss, entropy), alpha_grads = alpha_grad_fn(state.params)
+        print_nan(step, alpha_loss)
+        print_nan(step, alpha_grads)
+        state = state.alpha_apply_gradients(step=step, grads=alpha_grads)
+    else:
+        entropy = 0.0
+        alpha_loss = 0.0
+
+    return state, q_loss, pi_loss, alpha_loss, entropy
+
+
+@jax.jit
+def collect_experience(state: TrainState, replay_buffer_state,
+                       step_rng: PRNGKey, step):
+    """Collects experience by simulating."""
+    pi_rng = jax.random.fold_in(step_rng, step)
+    pi_rng, initialization_rng = jax.random.split(pi_rng)
+    pi_rng, goal_rng = jax.random.split(pi_rng)
+
+    observation = jax.lax.with_sharding_constraint(
+        state.problem.random_states(initialization_rng, FLAGS.num_agents),
+        state.sharding)
+
+    R = state.problem.random_goals(goal_rng, FLAGS.num_agents)
+
+    def loop(i, val):
+        """Runs 1 step of our simulation."""
+        observation, pi_rng, replay_buffer_state = val
+        pi_rng, action_rng = jax.random.split(pi_rng)
+        logging.info('Observation shape: %s', observation.shape)
+
+        def true_fn(i):
+            # We are at the beginning of the process, pick a random action.
+            return state.problem.random_actions(action_rng,
+                                                X=observation,
+                                                goal=R,
+                                                dimensions=FLAGS.num_agents)
+
+        def false_fn(i):
+            # We are past the beginning of the process, use the trained network.
+            pi_action, _, _ = state.pi_apply(rng=action_rng,
+                                             params=state.params,
+                                             observation=observation,
+                                             R=R,
+                                             deterministic=False)
+            return pi_action
+
+        pi_action = jax.lax.cond(
+            step <= FLAGS.random_sample_steps,
+            true_fn,
+            false_fn,
+            i,
+        )
+
+        # Compute the destination state.
+        observation2 = jax.vmap(
+            lambda o, pi: state.problem.integrate_dynamics(o, pi),
+            in_axes=(0, 0))(observation, pi_action)
+
+        reward = jax.vmap(state.problem.reward)(X=observation2,
+                                                U=pi_action,
+                                                goal=R)
+
+        replay_buffer_state = state.replay_buffer.add(
+            replay_buffer_state, {
+                'observations1': observation,
+                'observations2': observation2,
+                'actions': pi_action,
+                'rewards': reward.reshape((FLAGS.num_agents, 1)),
+                'goals': R,
+            })
+
+        return observation2, pi_rng, replay_buffer_state
+
+    # Run 1 horizon of simulation
+    final_observation, final_pi_rng, final_replay_buffer_state = jax.lax.fori_loop(
+        0, FLAGS.horizon + 1, loop, (observation, pi_rng, replay_buffer_state))
+
+    return state, final_replay_buffer_state
+
+
+@jax.jit
+def update_gradients(rng: PRNGKey, state: TrainState, replay_buffer_state,
+                     step: int):
+    rng, sample_rng = jax.random.split(rng)
+
+    def update_iteration(i, val):
+        rng, state, q_loss, pi_loss, alpha_loss, replay_buffer_state, entropy = val
+        rng, sample_rng, update_rng = jax.random.split(rng, 3)
+
+        batch = state.replay_buffer.sample(replay_buffer_state, sample_rng)
+
+        print_nan(i, replay_buffer_state)
+        print_nan(i, batch)
+
+        state, q_loss, pi_loss, alpha_loss, entropy = train_step(
+            state, data=batch.experience, update_rng=update_rng, step=i)
+
+        return rng, state, q_loss, pi_loss, alpha_loss, replay_buffer_state, entropy
+
+    rng, state, q_loss, pi_loss, alpha_loss, replay_buffer_state, entropy = jax.lax.fori_loop(
+        step, step + FLAGS.horizon + 1, update_iteration,
+        (rng, state, 0.0, 0.0, 0.0, replay_buffer_state, 0))
+
+    state = state.target_apply_gradients(step=state.step)
+
+    return rng, state, q_loss, pi_loss, alpha_loss, entropy
+
+
+def train(workdir: str, problem: Problem) -> train_state.TrainState:
+    """Trains a Soft Actor-Critic controller."""
+    rng = jax.random.key(0)
+    rng, r_rng = jax.random.split(rng)
+
+    run = aim.Run(repo='aim://127.0.0.1:53800')
+
+    run['hparams'] = {
+        'q_learning_rate': FLAGS.q_learning_rate,
+        'pi_learning_rate': FLAGS.pi_learning_rate,
+        'alpha_learning_rate': FLAGS.alpha_learning_rate,
+        'random_sample_steps': FLAGS.random_sample_steps,
+        'batch_size': FLAGS.batch_size,
+        'horizon': FLAGS.horizon,
+        'warmup_steps': FLAGS.warmup_steps,
+        'steps': FLAGS.steps,
+        'replay_size': FLAGS.replay_size,
+        'num_agents': FLAGS.num_agents,
+        'polyak': FLAGS.polyak,
+        'gamma': FLAGS.gamma,
+        'alpha': FLAGS.alpha,
+        'final_q_learning_rate': FLAGS.final_q_learning_rate,
+        'final_pi_learning_rate': FLAGS.final_pi_learning_rate,
+    }
+
+    # Setup TrainState
+    rng, init_rng = jax.random.split(rng)
+    q_learning_rate = create_learning_rate_fn(
+        base_learning_rate=FLAGS.q_learning_rate,
+        final_learning_rate=FLAGS.final_q_learning_rate)
+    pi_learning_rate = create_learning_rate_fn(
+        base_learning_rate=FLAGS.pi_learning_rate,
+        final_learning_rate=FLAGS.final_pi_learning_rate)
+    state = create_train_state(
+        init_rng,
+        problem,
+        q_learning_rate=q_learning_rate,
+        pi_learning_rate=pi_learning_rate,
+        alpha_learning_rate=FLAGS.alpha_learning_rate,
+    )
+    state = restore_checkpoint(state, workdir)
+
+    logging.debug(nn.get_sharding(state, state.mesh))
+
+    replay_buffer_state = state.replay_buffer.init({
+        'observations1':
+        jax.numpy.zeros((problem.num_states, )),
+        'observations2':
+        jax.numpy.zeros((problem.num_states, )),
+        'actions':
+        jax.numpy.zeros((problem.num_outputs, )),
+        'rewards':
+        jax.numpy.zeros((1, )),
+        'goals':
+        jax.numpy.zeros((problem.num_goals, )),
+    })
+
+    logging.debug(nn.get_sharding(replay_buffer_state, state.mesh))
+
+    # Number of gradients to accumulate before doing decent.
+    update_after = FLAGS.batch_size // FLAGS.num_agents
+
+    @partial(jax.jit, donate_argnums=(1, 2))
+    def train_loop(state: TrainState, replay_buffer_state, rng: PRNGKey,
+                   step: int):
+        rng, step_rng = jax.random.split(rng)
+        # Collect experience
+        state, replay_buffer_state = collect_experience(
+            state,
+            replay_buffer_state,
+            step_rng,
+            step,
+        )
+
+        def nop(rng, state, replay_buffer_state, step):
+            return rng, state.update_step(step=step), 0.0, 0.0, 0.0, 0.0
+
+        # Train
+        rng, state, q_loss, pi_loss, alpha_loss, entropy = jax.lax.cond(
+            step >= update_after, update_gradients, nop, rng, state,
+            replay_buffer_state, step)
+
+        return state, replay_buffer_state, rng, q_loss, pi_loss, alpha_loss, entropy
+
+    last_time = time.time()
+    for step in range(0, FLAGS.steps, FLAGS.horizon):
+        state, replay_buffer_state, rng, q_loss, pi_loss, alpha_loss, entropy = train_loop(
+            state, replay_buffer_state, rng, step)
+
+        if FLAGS.debug_nan and has_nan(state.params):
+            logging.fatal('Nan params, aborting')
+
+        logging.info(
+            'Step %s: q_loss=%s, pi_loss=%s, alpha_loss=%s, q_learning_rate=%s, pi_learning_rate=%s, alpha=%s, entropy=%s, random=%s',
+            step,
+            q_loss,
+            pi_loss,
+            alpha_loss,
+            q_learning_rate(step),
+            pi_learning_rate(step),
+            jax.numpy.exp(state.params['logalpha']),
+            entropy,
+            step <= FLAGS.random_sample_steps,
+        )
+
+        run.track(
+            {
+                'q_loss': float(q_loss),
+                'pi_loss': float(pi_loss),
+                'alpha_loss': float(alpha_loss),
+                'alpha': float(jax.numpy.exp(state.params['logalpha'])),
+                'entropy': entropy,
+            },
+            step=step)
+
+        if time.time() > last_time + 3.0 and step > update_after:
+            # TODO(austin): Simulate a rollout and accumulate the reward.  How good are we doing?
+            save_checkpoint(state, workdir)
+            last_time = time.time()
+
+    return state
diff --git a/scouting/scouting_test.cy.js b/scouting/scouting_test.cy.js
index 990e69f..7157880 100644
--- a/scouting/scouting_test.cy.js
+++ b/scouting/scouting_test.cy.js
@@ -119,7 +119,7 @@
       ' Ended Match; stageType: kHARMONY, trapNote: false, spotlight: false '
     );
   // Ensure that the penalties action is only submitted once.
-  cy.get('#review_data li').contains('Penalties').should('have.length', 1);
+  cy.get('#review_data li:contains("Penalties")').its('length').should('eq', 1);
 
   clickButton('Submit');
   headerShouldBe(teamNumber + ' Success ');
diff --git a/tools/python/requirements.lock.txt b/tools/python/requirements.lock.txt
index 93171a9..d465241 100644
--- a/tools/python/requirements.lock.txt
+++ b/tools/python/requirements.lock.txt
@@ -20,6 +20,116 @@
     #   tensorflow
     #   tensorflow-datasets
     #   tensorflow-metadata
+    #   tensorflow-probability
+aim==3.24.0 \
+    --hash=sha256:1266fac2453f2d356d2e39c98d15b46ba7a71ecab14cdaa6eaa6d390f5add898 \
+    --hash=sha256:1322659dcecb701c264f5067375c74811faf3514bb316e1ca1e53b9de6b62766 \
+    --hash=sha256:13dff702a680ad2d25344543e3b912c217a0fd305d5355f388fcd14f030af4f0 \
+    --hash=sha256:14a70cd508b4761d7d4e1f302207feb58906ac3ab27d2d64eeb4f1cbb8d4dc47 \
+    --hash=sha256:1789bcc9edf69ae90bb18a6f3fa4862095b8020eadc7e5e0e93ba4f242250947 \
+    --hash=sha256:29949cf7e5b5a46cff6a1d868805962e6563929934cd1d5d47678a58a4c9b777 \
+    --hash=sha256:2a9158717267e4f04ac12ffef8ef22c3e72af3b284ce4a86906a511d57ee98b9 \
+    --hash=sha256:2b0e41e6b46b6e435be845aeda4792cc6b392fb17bb5096e6ca186fffeb96547 \
+    --hash=sha256:2ea588e075a5508014af74be4821adc58041ac034af81b106936482043fcb124 \
+    --hash=sha256:39462568e7e4270574c20812b2ede4747e908c0320f947c39b94cdcbda63141b \
+    --hash=sha256:430000ece9e045d4b5313b0e683c363730b712260147834c4a6f89a2fd06513d \
+    --hash=sha256:4903a1ead28681dd5a51b4c8b613e6af5a158bde11d77678a64d6eeab9d9e97f \
+    --hash=sha256:663f939ebd89d053ca2a31f921cf2389f94b75fe3a97a66840b33ac0c8888b46 \
+    --hash=sha256:6937cb8736063e3734292f32aed8de141173be83d6dc9c49d8f05a58bb99a713 \
+    --hash=sha256:696aa9bb1c4316fb9171410daaff640293d5d2ee215055dd7eda27445318240b \
+    --hash=sha256:6b1b12e6724677c1bf9d9c62a0ddb30cc5b130080765fd217792e36a6622a3e3 \
+    --hash=sha256:8328b7703b7626f1f5082e947c5e203011536de039c64e551364444299ff68e1 \
+    --hash=sha256:8aff59858e5944ede0eb7ecbd56d4131418913a5cb13436dbe55e1795b85a838 \
+    --hash=sha256:92a794755de87c920bc1de49856a0ec864a903c2e4fb090a4fe6b0a71136c865 \
+    --hash=sha256:b2a2755115aa9b8efc57d262bef9ce9f13ca56068e6833bf359884228cab9803 \
+    --hash=sha256:c0f8dd9542bdf251b195d8c1680367b7c043a1fb59fd170944679157f2cf2b05 \
+    --hash=sha256:cb9d3e638598309e7e1d9970c62ec93d329ffcdeab7753886eee985b2b15a207 \
+    --hash=sha256:d52419e43d5a879455ca874843e5e45d4725022665a7c560f6b2193ad6a181a4 \
+    --hash=sha256:d63186f069f097de107a373fca2de9a5e7662c7d2ed4364b8937b5a5544e92f7 \
+    --hash=sha256:e481ef1e6e3ea17632fd4ecdee89cabb3f815929a5b080ee0e868e553f893c55 \
+    --hash=sha256:eaf98b0cba60d97cbce75a88ae96ce4c2439b3ba77572b9f17a5885fb76e9154 \
+    --hash=sha256:ec3bd85fdb5b85b9655d77fd0474e3f5c78f5065ca77c59efd77dbfae8005e40 \
+    --hash=sha256:f98f52fab910cdaee91256cf722e51b3edb131d9a0331519bccc9b6f06c28f6a
+    # via -r tools/python/requirements.txt
+aim-ui==3.24.0 \
+    --hash=sha256:d24ca6059095f76f29b4bee211b71dcfa5ed2e4fa6d16d82a343c900d5a37498
+    # via aim
+aimrecords==0.0.7 \
+    --hash=sha256:9b562fa5b5109b4b3dd4f83be0061cadbac63fa8031f281b8b5c8ae29967072f \
+    --hash=sha256:b9276890891c5fd68f817e20fc5d466a80c01e22fa468eaa979331448a75d601
+    # via aim
+aimrocks==0.5.2 \
+    --hash=sha256:03ca9bd3a7d379f40c678e648d3ec1445738a32fee337009cfb6aa9aedc51964 \
+    --hash=sha256:081b59cf3a02056420e32d8fa851859d314ae227e975d6febba67e9341135208 \
+    --hash=sha256:14982839f451f8990e9a1b5c4c06ffc77cafeb3b4a7f372f92a1da19a52a8a11 \
+    --hash=sha256:18574bab2cc060231a3da26a3ca2b18b6482b79649217e8fdcf6bc29efcdf973 \
+    --hash=sha256:1c1754ba5da8f2e016ed96b85eeb31048cc325cc351c32431d668ab226a0d986 \
+    --hash=sha256:2cfc3f4f1e4b105c1973007e4798aa3cedc0fc81436f81c220e02a00d796071c \
+    --hash=sha256:2d120e114c11882e8ac7dcd76a745b21da1fd0cd10aeaf525ec8a48a08556b3f \
+    --hash=sha256:3e580c5640c61e47591873448ddfd5741979f2bccf40809157fb260c6956f1e5 \
+    --hash=sha256:3f65583d29bcfc3baa422e45e73de89c4c781490664eb49c1a4c21c074f5bbfa \
+    --hash=sha256:4aaa2ffae1dbdcd2be21535a2866ec4a9a2fbb4338cc5b955ad6ca3fae22461c \
+    --hash=sha256:4ce617cf9f11e81a70070ea1d14fa2204996c651984cbd19178246eb33b143d0 \
+    --hash=sha256:533eda940f4bd1641fee15da09595c965d6890e449706fb3442174472b468a19 \
+    --hash=sha256:5c92e843818e7b764725c1dca1ca6744202ac46b5c246b407e39e8a28e0266a1 \
+    --hash=sha256:691621709f02841a248ed2555ec61346c50bfc07df2553be54a355c9010676e3 \
+    --hash=sha256:6b11d27df8ebec63bb9a121c55bc19c8b93801a6a9064533835e056bc5a11bb6 \
+    --hash=sha256:7452149a119d4b3620254a567c3c68ecfa3e016f58f443847e4fb70b85186593 \
+    --hash=sha256:76258350f2715d686d5da12a5a2df0d7b88e1b33e45052e0ddeb549c7497a56e \
+    --hash=sha256:762f7b41793165717a9e0589658cd81bffb54161295ec7403534d40692ac9281 \
+    --hash=sha256:7635741ed2b8dbf59c7564446bd0716dd5ea431c82753000ca4851bed9e76911 \
+    --hash=sha256:79400c6f4c72bcc4485f2a4411a3e6c1f6ead7a3928a00a72739abb1ef9ec0d3 \
+    --hash=sha256:7f47ae2f2183e1c1c9299be79ac9704b1d47e66c8ae7d41356385ad33e9def4b \
+    --hash=sha256:8b3364c566e547cd1855700cdec07149a139f6665a6ad60275e3ee3679945dbd \
+    --hash=sha256:8d685e8092db34c68ff8208c4961918345e14a0bdddf0ee22017346433950cc8 \
+    --hash=sha256:95dae89ed772439a12c845d013dca1dc3abb88ccd71ee50bc8728d43afddd7d7 \
+    --hash=sha256:96d6877437108ca8f8c3c72f27aeeb987af881ca6fe78a46962d3bf96346fd23 \
+    --hash=sha256:9becbd34b2bac33dae7db5ce85f9ef70b83b20fd547794a40b7a7bd846be45fa \
+    --hash=sha256:9c88bdacf4d977f80b3c9a7555b5e152945d66feccd6e0cc7d2135a7f477d6bc \
+    --hash=sha256:9d870581e402c718549385704d3bbb373aa6eb684b1e1bc5cb935af8ebba91b6 \
+    --hash=sha256:9db95c611b04cc4fb1796436c3e09483414636282261f5eae46c73f68bd9dce9 \
+    --hash=sha256:9de44918367c5f8f2f9b638f97c720320c5bb4fd400a76e4e94d34b6d7d41cc6 \
+    --hash=sha256:9faaecf4fe0335c27e63523f6a25e038877a33c63a261ff2192582e52493b39b \
+    --hash=sha256:a3be10ecd3373c35ce51b8b531c2ac41e11ff954ee678377512e8210a01b593b \
+    --hash=sha256:a9ba647f32934ac999c4119cbb8b59510dfe69aec98558539b84db7db9f20acf \
+    --hash=sha256:aba6d805b5370eda1c946c269d6df926a083819798603652c8f3b16469fea1d2 \
+    --hash=sha256:ada99031f85364232a5f8b6c3be0ef4835d26f03b09529c86b2b80c8b027428c \
+    --hash=sha256:b26c2d9adee42ce1611add5220567cab1a831813b0f711d7921cbaa0bf633a28 \
+    --hash=sha256:b5777e4aa7a5d2715c5bf698d4b4049d3f2b95bc0704d455ac486498820cd963 \
+    --hash=sha256:bba97b8bbe82b41e7aa52b64a80e1da5279e54153cb46a0364f9947c0655e5a8 \
+    --hash=sha256:bc9a4007ffad3d9a84188f8062ec2d2122283769956895a73e2336febc5ae8f1 \
+    --hash=sha256:be3a48210a2dc25633d53b0b7c33b362b7fce8f9fe2ad4ebb4cdc03471bdeb62 \
+    --hash=sha256:c338d07e80344e15e6c49d8c125f31492ac58c8236c82f7c0d8171c81027b4dc \
+    --hash=sha256:c98ca6955a43ed2c968ae9fe44bb1049f52d59ef319d9f78eb99dd4d3359a580 \
+    --hash=sha256:d4cc1523e7cd766937600da915b061538a44efec1f814b08b056eef3876e89cf \
+    --hash=sha256:d5e34571e930f99df9832cfeb7ad9917cbf0245ef2e3177cb82f86c29e1b273d \
+    --hash=sha256:d5e916f34a5d34d4da6a9199ece1c0d51efa93a30984ed89ad4ccaa1fb7a51c2 \
+    --hash=sha256:d74170021b17451881df18683eb0aa97417cb8b030b3dea425d7580891c22608 \
+    --hash=sha256:e018df19877ed13e93bbc8e8c32664cedade08d483eb0aa7077fc41b8eefd005 \
+    --hash=sha256:e6a79076d669dbf221442399da893baff6c1549031edbb5d556042d1b9b6525c \
+    --hash=sha256:e9a62a21266f88337e58d443ca58e85293232f543bcf0a66832fc89d4f9a320d \
+    --hash=sha256:eb4adb6bc4db3f0d3a1fe6cfec05846f76fabe5a3faeabc294c9777535351864 \
+    --hash=sha256:f479567d8514a63ee7f227d0841dc886870c37c3f6e17a8724ecaebfaa1331b2 \
+    --hash=sha256:f99ae65f910cf4a505457a280c9296212c9d844f5ece8c7d28813edf62787602 \
+    --hash=sha256:fe5b69e7dc54a07188d06fba9da012318223b60c07a96d39f90ccf1b01f833f7 \
+    --hash=sha256:ff6334af4ac403438eae330bf25fff5b3a63ba9f8f87a77ebb2d34815ef36431
+    # via aim
+aiofiles==24.1.0 \
+    --hash=sha256:22a075c9e5a3810f0c2e48f3008c94d68c65d763b9b03857924c99e57355166c \
+    --hash=sha256:b4ec55f4195e3eb5d7abd1bf7e061763e864dd4954231fb8539a0ef8bb8260e5
+    # via aim
+alembic==1.13.3 \
+    --hash=sha256:203503117415561e203aa14541740643a611f641517f0209fcae63e9fa09f1a2 \
+    --hash=sha256:908e905976d15235fae59c9ac42c4c5b75cfcefe3d27c0fbf7ae15a37715d80e
+    # via aim
+annotated-types==0.7.0 \
+    --hash=sha256:1f02e8b43a8fbbc3f3e0d4f0f4bfc8131bcb4eebe8849b8e5c773f3a1c582a53 \
+    --hash=sha256:aff07c09a53a08bc8cfccb9c85b05f1aa9a2a6f23728d790723543408344ce89
+    # via pydantic
+anyio==4.6.0 \
+    --hash=sha256:137b4559cbb034c477165047febb6ff83f390fc3b20bf181c1fc0a728cb8beeb \
+    --hash=sha256:c7d2e9d63e31599eeb636c8c5c03a7e108d73b345f064f1c19fdc87b79036a9a
+    # via starlette
 array-record==0.5.1 \
     --hash=sha256:248fb29086cb3a6322a5d8b8332d77713a030bc54f0bacdf215a6d3185f73f90 \
     --hash=sha256:6ebe99f37e3a797322f4f5cfc6902b5e852012ba2729fac628aad6affb225247 \
@@ -34,6 +144,10 @@
     --hash=sha256:5ad93a8456f0d084c3456d059fd9a92cce667963232cbf763eac3bc5b7940872 \
     --hash=sha256:c2652417f2c8b5bb325c885ae329bdf3f86424075c4fd1a128674bc6fba4b8e8
     # via tensorflow
+base58==2.0.1 \
+    --hash=sha256:365c9561d9babac1b5f18ee797508cd54937a724b6e419a130abad69cec5ca79 \
+    --hash=sha256:447adc750d6b642987ffc6d397ecd15a799852d5f6a1d308d384500243825058
+    # via aimrecords
 blinker==1.8.2 \
     --hash=sha256:1779309f71bf239144b9399d06ae925637cf6634cf6bd131104184531bf67c01 \
     --hash=sha256:8f77b09d3bf7c795e969e9486f39c2c5e9c39d4ee07424be2bc594ece9642d83
@@ -42,6 +156,20 @@
     --hash=sha256:b7c22fb0f7004b04f12e1b7b26ee0269a26737a08ded848fb58f6a34ec1eb155 \
     --hash=sha256:c6f33817f866fc67fbeb5df79cd13a8bb592c05c591f3fd7f4f22b824f7afa01
     # via -r tools/python/requirements.txt
+boto3==1.35.27 \
+    --hash=sha256:10d0fe15670b83a3f26572ab20d9152a064cee4c54b5ea9a1eeb1f0c3b807a7b \
+    --hash=sha256:3da139ca038032e92086e26d23833b557f0c257520162bfd3d6f580bf8032c86
+    # via aim
+botocore==1.35.27 \
+    --hash=sha256:c299c70b5330a8634e032883ce8a72c2c6d9fdbc985d8191199cb86b92e7cbbd \
+    --hash=sha256:f68875c26cd57a9d22c0f7a981ecb1636d7ce4d0e35797e04765b53e7bfed3e7
+    # via
+    #   boto3
+    #   s3transfer
+cachetools==5.5.0 \
+    --hash=sha256:02134e8439cdc2ffb62023ce1debca2944c3f289d66bb17ead3ab3dede74b292 \
+    --hash=sha256:2cc24fb4cbe39633fb7badd9db9ca6295d766d9c2995f245725a46715d050f2a
+    # via aim
 casadi==3.6.6 \
     --hash=sha256:0870df9ac7040c14b35fdc82b74578ccfe8f1d9d8615eb79693a560fefb42307 \
     --hash=sha256:0fd493876c673ad149b03513c4f72275611643f2225f4f5d7c7ff828f75805a1 \
@@ -97,6 +225,75 @@
     --hash=sha256:922820b53db7a7257ffbda3f597266d435245903d80737e34f8a45ff3e3230d8 \
     --hash=sha256:bec941d2aa8195e248a60b31ff9f0558284cf01a52591ceda73ea9afffd69fd9
     # via requests
+cffi==1.17.1 \
+    --hash=sha256:045d61c734659cc045141be4bae381a41d89b741f795af1dd018bfb532fd0df8 \
+    --hash=sha256:0984a4925a435b1da406122d4d7968dd861c1385afe3b45ba82b750f229811e2 \
+    --hash=sha256:0e2b1fac190ae3ebfe37b979cc1ce69c81f4e4fe5746bb401dca63a9062cdaf1 \
+    --hash=sha256:0f048dcf80db46f0098ccac01132761580d28e28bc0f78ae0d58048063317e15 \
+    --hash=sha256:1257bdabf294dceb59f5e70c64a3e2f462c30c7ad68092d01bbbfb1c16b1ba36 \
+    --hash=sha256:1c39c6016c32bc48dd54561950ebd6836e1670f2ae46128f67cf49e789c52824 \
+    --hash=sha256:1d599671f396c4723d016dbddb72fe8e0397082b0a77a4fab8028923bec050e8 \
+    --hash=sha256:28b16024becceed8c6dfbc75629e27788d8a3f9030691a1dbf9821a128b22c36 \
+    --hash=sha256:2bb1a08b8008b281856e5971307cc386a8e9c5b625ac297e853d36da6efe9c17 \
+    --hash=sha256:30c5e0cb5ae493c04c8b42916e52ca38079f1b235c2f8ae5f4527b963c401caf \
+    --hash=sha256:31000ec67d4221a71bd3f67df918b1f88f676f1c3b535a7eb473255fdc0b83fc \
+    --hash=sha256:386c8bf53c502fff58903061338ce4f4950cbdcb23e2902d86c0f722b786bbe3 \
+    --hash=sha256:3edc8d958eb099c634dace3c7e16560ae474aa3803a5df240542b305d14e14ed \
+    --hash=sha256:45398b671ac6d70e67da8e4224a065cec6a93541bb7aebe1b198a61b58c7b702 \
+    --hash=sha256:46bf43160c1a35f7ec506d254e5c890f3c03648a4dbac12d624e4490a7046cd1 \
+    --hash=sha256:4ceb10419a9adf4460ea14cfd6bc43d08701f0835e979bf821052f1805850fe8 \
+    --hash=sha256:51392eae71afec0d0c8fb1a53b204dbb3bcabcb3c9b807eedf3e1e6ccf2de903 \
+    --hash=sha256:5da5719280082ac6bd9aa7becb3938dc9f9cbd57fac7d2871717b1feb0902ab6 \
+    --hash=sha256:610faea79c43e44c71e1ec53a554553fa22321b65fae24889706c0a84d4ad86d \
+    --hash=sha256:636062ea65bd0195bc012fea9321aca499c0504409f413dc88af450b57ffd03b \
+    --hash=sha256:6883e737d7d9e4899a8a695e00ec36bd4e5e4f18fabe0aca0efe0a4b44cdb13e \
+    --hash=sha256:6b8b4a92e1c65048ff98cfe1f735ef8f1ceb72e3d5f0c25fdb12087a23da22be \
+    --hash=sha256:6f17be4345073b0a7b8ea599688f692ac3ef23ce28e5df79c04de519dbc4912c \
+    --hash=sha256:706510fe141c86a69c8ddc029c7910003a17353970cff3b904ff0686a5927683 \
+    --hash=sha256:72e72408cad3d5419375fc87d289076ee319835bdfa2caad331e377589aebba9 \
+    --hash=sha256:733e99bc2df47476e3848417c5a4540522f234dfd4ef3ab7fafdf555b082ec0c \
+    --hash=sha256:7596d6620d3fa590f677e9ee430df2958d2d6d6de2feeae5b20e82c00b76fbf8 \
+    --hash=sha256:78122be759c3f8a014ce010908ae03364d00a1f81ab5c7f4a7a5120607ea56e1 \
+    --hash=sha256:805b4371bf7197c329fcb3ead37e710d1bca9da5d583f5073b799d5c5bd1eee4 \
+    --hash=sha256:85a950a4ac9c359340d5963966e3e0a94a676bd6245a4b55bc43949eee26a655 \
+    --hash=sha256:8f2cdc858323644ab277e9bb925ad72ae0e67f69e804f4898c070998d50b1a67 \
+    --hash=sha256:9755e4345d1ec879e3849e62222a18c7174d65a6a92d5b346b1863912168b595 \
+    --hash=sha256:98e3969bcff97cae1b2def8ba499ea3d6f31ddfdb7635374834cf89a1a08ecf0 \
+    --hash=sha256:a08d7e755f8ed21095a310a693525137cfe756ce62d066e53f502a83dc550f65 \
+    --hash=sha256:a1ed2dd2972641495a3ec98445e09766f077aee98a1c896dcb4ad0d303628e41 \
+    --hash=sha256:a24ed04c8ffd54b0729c07cee15a81d964e6fee0e3d4d342a27b020d22959dc6 \
+    --hash=sha256:a45e3c6913c5b87b3ff120dcdc03f6131fa0065027d0ed7ee6190736a74cd401 \
+    --hash=sha256:a9b15d491f3ad5d692e11f6b71f7857e7835eb677955c00cc0aefcd0669adaf6 \
+    --hash=sha256:ad9413ccdeda48c5afdae7e4fa2192157e991ff761e7ab8fdd8926f40b160cc3 \
+    --hash=sha256:b2ab587605f4ba0bf81dc0cb08a41bd1c0a5906bd59243d56bad7668a6fc6c16 \
+    --hash=sha256:b62ce867176a75d03a665bad002af8e6d54644fad99a3c70905c543130e39d93 \
+    --hash=sha256:c03e868a0b3bc35839ba98e74211ed2b05d2119be4e8a0f224fba9384f1fe02e \
+    --hash=sha256:c59d6e989d07460165cc5ad3c61f9fd8f1b4796eacbd81cee78957842b834af4 \
+    --hash=sha256:c7eac2ef9b63c79431bc4b25f1cd649d7f061a28808cbc6c47b534bd789ef964 \
+    --hash=sha256:c9c3d058ebabb74db66e431095118094d06abf53284d9c81f27300d0e0d8bc7c \
+    --hash=sha256:ca74b8dbe6e8e8263c0ffd60277de77dcee6c837a3d0881d8c1ead7268c9e576 \
+    --hash=sha256:caaf0640ef5f5517f49bc275eca1406b0ffa6aa184892812030f04c2abf589a0 \
+    --hash=sha256:cdf5ce3acdfd1661132f2a9c19cac174758dc2352bfe37d98aa7512c6b7178b3 \
+    --hash=sha256:d016c76bdd850f3c626af19b0542c9677ba156e4ee4fccfdd7848803533ef662 \
+    --hash=sha256:d01b12eeeb4427d3110de311e1774046ad344f5b1a7403101878976ecd7a10f3 \
+    --hash=sha256:d63afe322132c194cf832bfec0dc69a99fb9bb6bbd550f161a49e9e855cc78ff \
+    --hash=sha256:da95af8214998d77a98cc14e3a3bd00aa191526343078b530ceb0bd710fb48a5 \
+    --hash=sha256:dd398dbc6773384a17fe0d3e7eeb8d1a21c2200473ee6806bb5e6a8e62bb73dd \
+    --hash=sha256:de2ea4b5833625383e464549fec1bc395c1bdeeb5f25c4a3a82b5a8c756ec22f \
+    --hash=sha256:de55b766c7aa2e2a3092c51e0483d700341182f08e67c63630d5b6f200bb28e5 \
+    --hash=sha256:df8b1c11f177bc2313ec4b2d46baec87a5f3e71fc8b45dab2ee7cae86d9aba14 \
+    --hash=sha256:e03eab0a8677fa80d646b5ddece1cbeaf556c313dcfac435ba11f107ba117b5d \
+    --hash=sha256:e221cf152cff04059d011ee126477f0d9588303eb57e88923578ace7baad17f9 \
+    --hash=sha256:e31ae45bc2e29f6b2abd0de1cc3b9d5205aa847cafaecb8af1476a609a2f6eb7 \
+    --hash=sha256:edae79245293e15384b51f88b00613ba9f7198016a5948b5dddf4917d4d26382 \
+    --hash=sha256:f1e22e8c4419538cb197e4dd60acc919d7696e5ef98ee4da4e01d3f8cfa4cc5a \
+    --hash=sha256:f3a2b4222ce6b60e2e8b337bb9596923045681d71e5a082783484d845390938e \
+    --hash=sha256:f6a16c31041f09ead72d69f583767292f750d24913dadacf5756b966aacb3f1a \
+    --hash=sha256:f75c7ab1f9e4aca5414ed4d8e5c0e303a34f4421f8a0d47a4d019ceff0ab6af4 \
+    --hash=sha256:f79fc4fc25f1c8698ff97788206bb3c2598949bfe0fef03d299eb1b5356ada99 \
+    --hash=sha256:f7f5baafcc48261359e14bcd6d9bff6d4b28d9103847c9e136694cb0501aef87 \
+    --hash=sha256:fc48c783f9c87e60831201f2cce7f3b2e4846bf4d8728eabe54d60700b318a0b
+    # via cryptography
 charset-normalizer==3.3.2 \
     --hash=sha256:06435b539f889b1f6f4ac1758871aae42dc3a8c0e24ac9e60c2384973ad73027 \
     --hash=sha256:06a81e93cd441c56a9b65d8e1d043daeb97a3d0856d177d5c90ba85acb3db087 \
@@ -199,9 +396,15 @@
     --hash=sha256:ae74fb96c20a0277a1d615f1e4d73c8414f5a98db8b799a7931d1582f3390c28 \
     --hash=sha256:ca9853ad459e787e2192211578cc907e7594e294c7ccc834310722b41b9ca6de
     # via
+    #   aim
     #   flask
     #   mkdocs
     #   tensorflow-datasets
+    #   uvicorn
+cloudpickle==3.1.0 \
+    --hash=sha256:81a929b6e3c7335c863c771d673d105f02efdb89dfaba0c90495d1c64796601b \
+    --hash=sha256:fe11acda67f61aaaec473e3afe030feb131d78a43461b718185363384f1ba12e
+    # via tensorflow-probability
 clu==0.0.12 \
     --hash=sha256:0d183e7d25f7dd0700444510a264e24700e2f068bdabd199ed22866f7e54edba \
     --hash=sha256:f71eaa1afbd30f57f7709257ba7e1feb8ad5c1c3dcae3606672a138678bb3ce4
@@ -279,10 +482,43 @@
     # via
     #   bokeh
     #   matplotlib
+cryptography==43.0.1 \
+    --hash=sha256:014f58110f53237ace6a408b5beb6c427b64e084eb451ef25a28308270086494 \
+    --hash=sha256:1bbcce1a551e262dfbafb6e6252f1ae36a248e615ca44ba302df077a846a8806 \
+    --hash=sha256:203e92a75716d8cfb491dc47c79e17d0d9207ccffcbcb35f598fbe463ae3444d \
+    --hash=sha256:27e613d7077ac613e399270253259d9d53872aaf657471473ebfc9a52935c062 \
+    --hash=sha256:2bd51274dcd59f09dd952afb696bf9c61a7a49dfc764c04dd33ef7a6b502a1e2 \
+    --hash=sha256:38926c50cff6f533f8a2dae3d7f19541432610d114a70808f0926d5aaa7121e4 \
+    --hash=sha256:511f4273808ab590912a93ddb4e3914dfd8a388fed883361b02dea3791f292e1 \
+    --hash=sha256:58d4e9129985185a06d849aa6df265bdd5a74ca6e1b736a77959b498e0505b85 \
+    --hash=sha256:5b43d1ea6b378b54a1dc99dd8a2b5be47658fe9a7ce0a58ff0b55f4b43ef2b84 \
+    --hash=sha256:61ec41068b7b74268fa86e3e9e12b9f0c21fcf65434571dbb13d954bceb08042 \
+    --hash=sha256:666ae11966643886c2987b3b721899d250855718d6d9ce41b521252a17985f4d \
+    --hash=sha256:68aaecc4178e90719e95298515979814bda0cbada1256a4485414860bd7ab962 \
+    --hash=sha256:7c05650fe8023c5ed0d46793d4b7d7e6cd9c04e68eabe5b0aeea836e37bdcec2 \
+    --hash=sha256:80eda8b3e173f0f247f711eef62be51b599b5d425c429b5d4ca6a05e9e856baa \
+    --hash=sha256:8385d98f6a3bf8bb2d65a73e17ed87a3ba84f6991c155691c51112075f9ffc5d \
+    --hash=sha256:88cce104c36870d70c49c7c8fd22885875d950d9ee6ab54df2745f83ba0dc365 \
+    --hash=sha256:9d3cdb25fa98afdd3d0892d132b8d7139e2c087da1712041f6b762e4f807cc96 \
+    --hash=sha256:a575913fb06e05e6b4b814d7f7468c2c660e8bb16d8d5a1faf9b33ccc569dd47 \
+    --hash=sha256:ac119bb76b9faa00f48128b7f5679e1d8d437365c5d26f1c2c3f0da4ce1b553d \
+    --hash=sha256:c1332724be35d23a854994ff0b66530119500b6053d0bd3363265f7e5e77288d \
+    --hash=sha256:d03a475165f3134f773d1388aeb19c2d25ba88b6a9733c5c590b9ff7bbfa2e0c \
+    --hash=sha256:d75601ad10b059ec832e78823b348bfa1a59f6b8d545db3a24fd44362a1564cb \
+    --hash=sha256:de41fd81a41e53267cb020bb3a7212861da53a7d39f863585d13ea11049cf277 \
+    --hash=sha256:e710bf40870f4db63c3d7d929aa9e09e4e7ee219e703f949ec4073b4294f6172 \
+    --hash=sha256:ea25acb556320250756e53f9e20a4177515f012c9eaea17eb7587a8c4d8ae034 \
+    --hash=sha256:f98bf604c82c416bc829e490c700ca1553eafdf2912a91e23a79d97d9801372a \
+    --hash=sha256:fba1007b3ef89946dbbb515aeeb41e30203b004f0b4b00e5e16078b518563289
+    # via aim
 cycler==0.12.1 \
     --hash=sha256:85cef7cff222d8644161529808465972e51340599459b8ac3ccbac5a854e0d30 \
     --hash=sha256:88bb128f02ba341da8ef447245a9e138fae777f6a23943da4540077d3601eb1c
     # via matplotlib
+decorator==5.1.1 \
+    --hash=sha256:637996211036b6385ef91435e4fae22989472f9d571faba8927ba8253acbc330 \
+    --hash=sha256:b8c3f85900b9dc423225913c5aace94729fe1fa9763b38939a95226f02d37186
+    # via tensorflow-probability
 dm-tree==0.1.8 \
     --hash=sha256:054b461f8176f4bce7a21f7b1870f873a1ced3bdbe1282c816c550bb43c71fa6 \
     --hash=sha256:09964470f76a5201aff2e8f9b26842976de7889300676f927930f6285e256760 \
@@ -330,7 +566,9 @@
     --hash=sha256:ea9e59e0451e7d29aece402d9f908f2e2a80922bcde2ebfd5dcb07750fcbfee8 \
     --hash=sha256:f7ac31b9aecccb2c6e1ab29706f6ded3eba0c2c69c770322c9c685929c3d6afb \
     --hash=sha256:fa42a605d099ee7d41ba2b5fb75e21423951fd26e5d50583a00471238fb3021d
-    # via tensorflow-datasets
+    # via
+    #   tensorflow-datasets
+    #   tensorflow-probability
 etils[enp,epath,epy,etree]==1.5.2 \
     --hash=sha256:6dc882d355e1e98a5d1a148d6323679dc47c9a5792939b9de72615aa4737eb0b \
     --hash=sha256:ba6a3e1aff95c769130776aa176c11540637f5dd881f3b79172a5149b6b1c446
@@ -340,6 +578,18 @@
     #   optax
     #   orbax-checkpoint
     #   tensorflow-datasets
+exceptiongroup==1.2.2 \
+    --hash=sha256:3111b9d131c238bec2f8f516e123e14ba243563fb135d3fe885990585aa7795b \
+    --hash=sha256:47c2edf7c6738fafb49fd34290706d1a1a2f4d1c6df275526b62cbb4aa5393cc
+    # via anyio
+fastapi==0.115.0 \
+    --hash=sha256:17ea427674467486e997206a5ab25760f6b09e069f099b96f5b55a32fb6f1631 \
+    --hash=sha256:f93b4ca3529a8ebc6fc3fcf710e5efa8de3df9b41570958abf1d97d843138004
+    # via aim
+filelock==3.16.1 \
+    --hash=sha256:2082e5703d51fbf98ea75855d9d5527e33d8ff23099bec374a134febee6946b0 \
+    --hash=sha256:c249fbfcd5db47e5e2d6d62198e565475ee65e4831e2561c8e313fa7eb961435
+    # via aim
 flashbax==0.1.2 \
     --hash=sha256:ac50b2580808ce63787da0ae240db14986e3404ade98a33335e6d7a5efe84859 \
     --hash=sha256:b566ac5a78975b3e0a0a404a8844a26aa45e9cacfaad2829dcbcac2ffb3d5f7a
@@ -410,7 +660,9 @@
 gast==0.6.0 \
     --hash=sha256:52b182313f7330389f72b069ba00f174cfe2a06411099547288839c6cbafbd54 \
     --hash=sha256:88fc5300d32c7ac6ca7b515310862f71e6fdf2c029bbec7c66c0f5dd47b6b1fb
-    # via tensorflow
+    # via
+    #   tensorflow
+    #   tensorflow-probability
 ghp-import==2.1.0 \
     --hash=sha256:8337dd7b50877f163d4c0289bc1f1c7f127550241988d568c1db512c4324a619 \
     --hash=sha256:9c535c4c61193c2df8871222567d7fd7e5014d835f97dc7b7439069e2413d343
@@ -424,6 +676,81 @@
     --hash=sha256:b32482794a366b5366a32c92a9a9201b107821889935a02b3e51f6b432ea84ed \
     --hash=sha256:c9f2c8dfc8f96d0d5808299920721be30c9eec37f2389f28904f454565c8a16e
     # via tensorflow
+greenlet==3.1.1 \
+    --hash=sha256:0153404a4bb921f0ff1abeb5ce8a5131da56b953eda6e14b88dc6bbc04d2049e \
+    --hash=sha256:03a088b9de532cbfe2ba2034b2b85e82df37874681e8c470d6fb2f8c04d7e4b7 \
+    --hash=sha256:04b013dc07c96f83134b1e99888e7a79979f1a247e2a9f59697fa14b5862ed01 \
+    --hash=sha256:05175c27cb459dcfc05d026c4232f9de8913ed006d42713cb8a5137bd49375f1 \
+    --hash=sha256:09fc016b73c94e98e29af67ab7b9a879c307c6731a2c9da0db5a7d9b7edd1159 \
+    --hash=sha256:0bbae94a29c9e5c7e4a2b7f0aae5c17e8e90acbfd3bf6270eeba60c39fce3563 \
+    --hash=sha256:0fde093fb93f35ca72a556cf72c92ea3ebfda3d79fc35bb19fbe685853869a83 \
+    --hash=sha256:1443279c19fca463fc33e65ef2a935a5b09bb90f978beab37729e1c3c6c25fe9 \
+    --hash=sha256:1776fd7f989fc6b8d8c8cb8da1f6b82c5814957264d1f6cf818d475ec2bf6395 \
+    --hash=sha256:1d3755bcb2e02de341c55b4fca7a745a24a9e7212ac953f6b3a48d117d7257aa \
+    --hash=sha256:23f20bb60ae298d7d8656c6ec6db134bca379ecefadb0b19ce6f19d1f232a942 \
+    --hash=sha256:275f72decf9932639c1c6dd1013a1bc266438eb32710016a1c742df5da6e60a1 \
+    --hash=sha256:2846930c65b47d70b9d178e89c7e1a69c95c1f68ea5aa0a58646b7a96df12441 \
+    --hash=sha256:3319aa75e0e0639bc15ff54ca327e8dc7a6fe404003496e3c6925cd3142e0e22 \
+    --hash=sha256:346bed03fe47414091be4ad44786d1bd8bef0c3fcad6ed3dee074a032ab408a9 \
+    --hash=sha256:36b89d13c49216cadb828db8dfa6ce86bbbc476a82d3a6c397f0efae0525bdd0 \
+    --hash=sha256:37b9de5a96111fc15418819ab4c4432e4f3c2ede61e660b1e33971eba26ef9ba \
+    --hash=sha256:396979749bd95f018296af156201d6211240e7a23090f50a8d5d18c370084dc3 \
+    --hash=sha256:3b2813dc3de8c1ee3f924e4d4227999285fd335d1bcc0d2be6dc3f1f6a318ec1 \
+    --hash=sha256:411f015496fec93c1c8cd4e5238da364e1da7a124bcb293f085bf2860c32c6f6 \
+    --hash=sha256:47da355d8687fd65240c364c90a31569a133b7b60de111c255ef5b606f2ae291 \
+    --hash=sha256:48ca08c771c268a768087b408658e216133aecd835c0ded47ce955381105ba39 \
+    --hash=sha256:4afe7ea89de619adc868e087b4d2359282058479d7cfb94970adf4b55284574d \
+    --hash=sha256:4ce3ac6cdb6adf7946475d7ef31777c26d94bccc377e070a7986bd2d5c515467 \
+    --hash=sha256:4ead44c85f8ab905852d3de8d86f6f8baf77109f9da589cb4fa142bd3b57b475 \
+    --hash=sha256:54558ea205654b50c438029505def3834e80f0869a70fb15b871c29b4575ddef \
+    --hash=sha256:5e06afd14cbaf9e00899fae69b24a32f2196c19de08fcb9f4779dd4f004e5e7c \
+    --hash=sha256:62ee94988d6b4722ce0028644418d93a52429e977d742ca2ccbe1c4f4a792511 \
+    --hash=sha256:63e4844797b975b9af3a3fb8f7866ff08775f5426925e1e0bbcfe7932059a12c \
+    --hash=sha256:6510bf84a6b643dabba74d3049ead221257603a253d0a9873f55f6a59a65f822 \
+    --hash=sha256:667a9706c970cb552ede35aee17339a18e8f2a87a51fba2ed39ceeeb1004798a \
+    --hash=sha256:6ef9ea3f137e5711f0dbe5f9263e8c009b7069d8a1acea822bd5e9dae0ae49c8 \
+    --hash=sha256:7017b2be767b9d43cc31416aba48aab0d2309ee31b4dbf10a1d38fb7972bdf9d \
+    --hash=sha256:7124e16b4c55d417577c2077be379514321916d5790fa287c9ed6f23bd2ffd01 \
+    --hash=sha256:73aaad12ac0ff500f62cebed98d8789198ea0e6f233421059fa68a5aa7220145 \
+    --hash=sha256:77c386de38a60d1dfb8e55b8c1101d68c79dfdd25c7095d51fec2dd800892b80 \
+    --hash=sha256:7876452af029456b3f3549b696bb36a06db7c90747740c5302f74a9e9fa14b13 \
+    --hash=sha256:7939aa3ca7d2a1593596e7ac6d59391ff30281ef280d8632fa03d81f7c5f955e \
+    --hash=sha256:8320f64b777d00dd7ccdade271eaf0cad6636343293a25074cc5566160e4de7b \
+    --hash=sha256:85f3ff71e2e60bd4b4932a043fbbe0f499e263c628390b285cb599154a3b03b1 \
+    --hash=sha256:8b8b36671f10ba80e159378df9c4f15c14098c4fd73a36b9ad715f057272fbef \
+    --hash=sha256:93147c513fac16385d1036b7e5b102c7fbbdb163d556b791f0f11eada7ba65dc \
+    --hash=sha256:935e943ec47c4afab8965954bf49bfa639c05d4ccf9ef6e924188f762145c0ff \
+    --hash=sha256:94b6150a85e1b33b40b1464a3f9988dcc5251d6ed06842abff82e42632fac120 \
+    --hash=sha256:94ebba31df2aa506d7b14866fed00ac141a867e63143fe5bca82a8e503b36437 \
+    --hash=sha256:95ffcf719966dd7c453f908e208e14cde192e09fde6c7186c8f1896ef778d8cd \
+    --hash=sha256:98884ecf2ffb7d7fe6bd517e8eb99d31ff7855a840fa6d0d63cd07c037f6a981 \
+    --hash=sha256:99cfaa2110534e2cf3ba31a7abcac9d328d1d9f1b95beede58294a60348fba36 \
+    --hash=sha256:9e8f8c9cb53cdac7ba9793c276acd90168f416b9ce36799b9b885790f8ad6c0a \
+    --hash=sha256:a0dfc6c143b519113354e780a50381508139b07d2177cb6ad6a08278ec655798 \
+    --hash=sha256:b2795058c23988728eec1f36a4e5e4ebad22f8320c85f3587b539b9ac84128d7 \
+    --hash=sha256:b42703b1cf69f2aa1df7d1030b9d77d3e584a70755674d60e710f0af570f3761 \
+    --hash=sha256:b7cede291382a78f7bb5f04a529cb18e068dd29e0fb27376074b6d0317bf4dd0 \
+    --hash=sha256:b8a678974d1f3aa55f6cc34dc480169d58f2e6d8958895d68845fa4ab566509e \
+    --hash=sha256:b8da394b34370874b4572676f36acabac172602abf054cbc4ac910219f3340af \
+    --hash=sha256:c3a701fe5a9695b238503ce5bbe8218e03c3bcccf7e204e455e7462d770268aa \
+    --hash=sha256:c4aab7f6381f38a4b42f269057aee279ab0fc7bf2e929e3d4abfae97b682a12c \
+    --hash=sha256:ca9d0ff5ad43e785350894d97e13633a66e2b50000e8a183a50a88d834752d42 \
+    --hash=sha256:d0028e725ee18175c6e422797c407874da24381ce0690d6b9396c204c7f7276e \
+    --hash=sha256:d21e10da6ec19b457b82636209cbe2331ff4306b54d06fa04b7c138ba18c8a81 \
+    --hash=sha256:d5e975ca70269d66d17dd995dafc06f1b06e8cb1ec1e9ed54c1d1e4a7c4cf26e \
+    --hash=sha256:da7a9bff22ce038e19bf62c4dd1ec8391062878710ded0a845bcf47cc0200617 \
+    --hash=sha256:db32b5348615a04b82240cc67983cb315309e88d444a288934ee6ceaebcad6cc \
+    --hash=sha256:dcc62f31eae24de7f8dce72134c8651c58000d3b1868e01392baea7c32c247de \
+    --hash=sha256:dfc59d69fc48664bc693842bd57acfdd490acafda1ab52c7836e3fc75c90a111 \
+    --hash=sha256:e347b3bfcf985a05e8c0b7d462ba6f15b1ee1c909e2dcad795e49e91b152c383 \
+    --hash=sha256:e4d333e558953648ca09d64f13e6d8f0523fa705f51cae3f03b5983489958c70 \
+    --hash=sha256:ed10eac5830befbdd0c32f83e8aa6288361597550ba669b04c48f0f9a2c843c6 \
+    --hash=sha256:efc0f674aa41b92da8c49e0346318c6075d734994c3c4e4430b1c3f853e498e4 \
+    --hash=sha256:f1695e76146579f8c06c1509c7ce4dfe0706f49c6831a817ac04eebb2fd02011 \
+    --hash=sha256:f1d4aeb8891338e60d1ab6127af1fe45def5259def8094b9c7e34690c8858803 \
+    --hash=sha256:f406b22b7c9a9b4f8aa9d2ab13d6ae0ac3e85c9a809bd590ad53fed2bf70dc79 \
+    --hash=sha256:f6ff3b14f2df4c41660a7dec01045a045653998784bf8cfcb5a525bdffffbc8f
+    # via sqlalchemy
 grpcio==1.66.1 \
     --hash=sha256:0e6c9b42ded5d02b6b1fea3a25f036a2236eeb75d0579bfd43c0018c88bf0a3e \
     --hash=sha256:161d5c535c2bdf61b95080e7f0f017a1dfcb812bf54093e71e5562b16225b4ce \
@@ -474,6 +801,10 @@
     # via
     #   tensorboard
     #   tensorflow
+h11==0.14.0 \
+    --hash=sha256:8f19fbbe99e72420ff35c00b27a34cb9937e902a8b810e2c88300c6f0a3b699d \
+    --hash=sha256:e3fe4ac4b851c468cc8363d500db52c2ead036020723024a109d37346efaa761
+    # via uvicorn
 h5py==3.11.0 \
     --hash=sha256:083e0329ae534a264940d6513f47f5ada617da536d8dccbafc3026aefc33c90e \
     --hash=sha256:1625fd24ad6cfc9c1ccd44a66dac2396e7ee74940776792772819fc69f3a3731 \
@@ -506,7 +837,9 @@
 idna==3.8 \
     --hash=sha256:050b4e5baadcd44d760cedbd2b8e639f2ff89bbc7a5730fcc662954303377aac \
     --hash=sha256:d838c2c0ed6fced7693d5e8ab8e734d5f8fda53a039c0164afb0b82e771e3603
-    # via requests
+    # via
+    #   anyio
+    #   requests
 importlib-metadata==8.4.0 \
     --hash=sha256:66f342cc6ac9818fc6ff340576acd24d65ba0b3efabb2b4ac08b598965a4a2f1 \
     --hash=sha256:9a547d3bc3608b025f93d403fdd1aae741c24fbb8314df4b155675742ce303c5
@@ -589,9 +922,16 @@
     --hash=sha256:bc5dd2abb727a5319567b7a813e6a2e7318c39f4f487cfe6c89c6f9c7d25197d
     # via
     #   -r tools/python/requirements.txt
+    #   aim
     #   bokeh
     #   flask
     #   mkdocs
+jmespath==1.0.1 \
+    --hash=sha256:02e2e4cc71b5bcab88332eebf907519190dd9e6e82107fa7f83b1003a6252980 \
+    --hash=sha256:90261b206d6defd58fdd5e85f478bf633a2901798906be2ad389150c5c60edbe
+    # via
+    #   boto3
+    #   botocore
 keras==3.5.0 \
     --hash=sha256:53ae4f9472ec9d9c6941c82a3fda86969724ace3b7630a94ba0a1f17ba1065c3 \
     --hash=sha256:d37a3c623935713473ceb25241b52bce9d1e0ff5b36e5d0f6f47ed55f8500c9a
@@ -703,6 +1043,10 @@
     --hash=sha256:c533091d8a3bbf7460a00cb6c1a71da93bffe148f172c7d03b1c31fbf8aa2a0b \
     --hash=sha256:cf4a99b05376513717ab5d82a0db832c56ccea4fd61a69dbb7bccf2dfb207dbe
     # via tensorflow
+mako==1.3.5 \
+    --hash=sha256:260f1dbc3a519453a9c856dedfe4beb4e50bd5a26d96386cb6c80856556bb91a \
+    --hash=sha256:48dbc20568c1d276a2698b36d968fa76161bf127194907ea6fc594fa81f943bc
+    # via alembic
 markdown==3.7 \
     --hash=sha256:2ae2471477cfd02dbbf038d5d9bc226d40def84b4fe2986e49b59b6b472bbed2 \
     --hash=sha256:7eb6df5690b81a1d7942992c97fad2938e956e79df20cbc6186e9c3a77b1c803
@@ -776,6 +1120,7 @@
     --hash=sha256:ffee1f21e5ef0d712f9033568f8344d5da8cc2869dbd08d87c84656e6a2d2f68
     # via
     #   jinja2
+    #   mako
     #   mkdocs
     #   werkzeug
 matplotlib==3.9.2 \
@@ -976,6 +1321,7 @@
     --hash=sha256:ffa75af20b44f8dba823498024771d5ac50620e6915abac414251bd971b4529f
     # via
     #   -r tools/python/requirements.txt
+    #   aim
     #   bokeh
     #   casadi
     #   chex
@@ -1002,6 +1348,7 @@
     #   tensorboard
     #   tensorflow
     #   tensorflow-datasets
+    #   tensorflow-probability
     #   tensorstore
 nvidia-cublas-cu12==12.6.1.4 \
     --hash=sha256:5dd125ece5469dbdceebe2e9536ad8fc4abd38aa394a7ace42fc8a930a1e81e3 \
@@ -1195,11 +1542,13 @@
     --hash=sha256:026ed72c8ed3fcce5bf8950572258698927fd1dbda10a5e981cdf0ac37f4f002 \
     --hash=sha256:5b8f2217dbdbd2f7f384c41c628544e6d52f2d0f53c6d0c3ea61aa5d1d7ff124
     # via
+    #   aim
     #   bokeh
     #   clu
     #   keras
     #   matplotlib
     #   mkdocs
+    #   plotly
     #   tensorboard
     #   tensorflow
 pandas==2.2.2 \
@@ -1319,6 +1668,7 @@
     --hash=sha256:ff25afb18123cea58a591ea0244b92eb1e61a1fd497bf6d6384f09bc3262ec3e \
     --hash=sha256:ff337c552345e95702c5fde3158acb0625111017d0e5f24bf3acdb9cc16b90d1
     # via
+    #   aim
     #   bokeh
     #   matplotlib
 pkginfo==1.11.1 \
@@ -1331,6 +1681,10 @@
     # via
     #   mkdocs-get-deps
     #   yapf
+plotly==5.24.1 \
+    --hash=sha256:dbc8ac8339d248a4bcc36e08a5659bacfe1b079390b8953533f4eb22169b4bae \
+    --hash=sha256:f67073a1e637eb0dc3e46324d9d51e2fe76e9727c892dde64ddf1e1b51f29089
+    # via -r tools/python/requirements.txt
 promise==2.3 \
     --hash=sha256:dfd18337c523ba4b6a58801c164c1904a9d4d1b1747c7d5dbf45b693a49d93d0
     # via tensorflow-datasets
@@ -1381,7 +1735,9 @@
     --hash=sha256:e2e8d0054fc88153ca0544f5c4d554d42e33df2e009c4ff42284ac9ebdef4132 \
     --hash=sha256:fc8c9510cde0146432bbdb433322861ee8c3efbf8589865c8bf8d21cb30c4d14 \
     --hash=sha256:ffe7fc9b6b36beadc8c322f84e1caff51e8703b88eee1da46d1e3a6ae11b4fd0
-    # via tensorflow-datasets
+    # via
+    #   aim
+    #   tensorflow-datasets
 pycairo==1.26.1 \
     --hash=sha256:067191315c3b4d09cad1ec57cdb8fc1d72e2574e89389c268a94f22d4fa98b5f \
     --hash=sha256:22e1db531d4ed3167a98f0ea165bfa2a30df9d6eb22361c38158c031065999a4 \
@@ -1399,6 +1755,105 @@
     --hash=sha256:ce049930e294c29b53c68dcaab3df97cc5de7eb1d3d8e8a9f5c77e7164cd6e85 \
     --hash=sha256:e68300d1c2196d1d34de3432885ae9ff78e10426fa16f765742a11c6f8fe0a71
     # via pygobject
+pycparser==2.22 \
+    --hash=sha256:491c8be9c040f5390f5bf44a5b07752bd07f56edf992381b05c701439eec10f6 \
+    --hash=sha256:c3702b6d3dd8c7abc1afa565d7e63d53a1d0bd86cdc24edd75470f4de499cfcc
+    # via cffi
+pydantic==2.9.2 \
+    --hash=sha256:d155cef71265d1e9807ed1c32b4c8deec042a44a50a4188b25ac67ecd81a9c0f \
+    --hash=sha256:f048cec7b26778210e28a0459867920654d48e5e62db0958433636cde4254f12
+    # via fastapi
+pydantic-core==2.23.4 \
+    --hash=sha256:0a7df63886be5e270da67e0966cf4afbae86069501d35c8c1b3b6c168f42cb36 \
+    --hash=sha256:0cb3da3fd1b6a5d0279a01877713dbda118a2a4fc6f0d821a57da2e464793f05 \
+    --hash=sha256:0dbd8dbed2085ed23b5c04afa29d8fd2771674223135dc9bc937f3c09284d071 \
+    --hash=sha256:0dff76e0602ca7d4cdaacc1ac4c005e0ce0dcfe095d5b5259163a80d3a10d327 \
+    --hash=sha256:1278e0d324f6908e872730c9102b0112477a7f7cf88b308e4fc36ce1bdb6d58c \
+    --hash=sha256:128585782e5bfa515c590ccee4b727fb76925dd04a98864182b22e89a4e6ed36 \
+    --hash=sha256:1498bec4c05c9c787bde9125cfdcc63a41004ff167f495063191b863399b1a29 \
+    --hash=sha256:19442362866a753485ba5e4be408964644dd6a09123d9416c54cd49171f50744 \
+    --hash=sha256:1b84d168f6c48fabd1f2027a3d1bdfe62f92cade1fb273a5d68e621da0e44e6d \
+    --hash=sha256:1e90d2e3bd2c3863d48525d297cd143fe541be8bbf6f579504b9712cb6b643ec \
+    --hash=sha256:20152074317d9bed6b7a95ade3b7d6054845d70584216160860425f4fbd5ee9e \
+    --hash=sha256:216f9b2d7713eb98cb83c80b9c794de1f6b7e3145eef40400c62e86cee5f4e1e \
+    --hash=sha256:233710f069d251feb12a56da21e14cca67994eab08362207785cf8c598e74577 \
+    --hash=sha256:255a8ef062cbf6674450e668482456abac99a5583bbafb73f9ad469540a3a232 \
+    --hash=sha256:2584f7cf844ac4d970fba483a717dbe10c1c1c96a969bf65d61ffe94df1b2863 \
+    --hash=sha256:2971bb5ffe72cc0f555c13e19b23c85b654dd2a8f7ab493c262071377bfce9f6 \
+    --hash=sha256:29d2c342c4bc01b88402d60189f3df065fb0dda3654744d5a165a5288a657368 \
+    --hash=sha256:2e203fdf807ac7e12ab59ca2bfcabb38c7cf0b33c41efeb00f8e5da1d86af480 \
+    --hash=sha256:33e3d65a85a2a4a0dc3b092b938a4062b1a05f3a9abde65ea93b233bca0e03f2 \
+    --hash=sha256:374a5e5049eda9e0a44c696c7ade3ff355f06b1fe0bb945ea3cac2bc336478a2 \
+    --hash=sha256:37b0fe330e4a58d3c58b24d91d1eb102aeec675a3db4c292ec3928ecd892a9a6 \
+    --hash=sha256:3d5639516376dce1940ea36edf408c554475369f5da2abd45d44621cb616f769 \
+    --hash=sha256:42c6dcb030aefb668a2b7009c85b27f90e51e6a3b4d5c9bc4c57631292015b0d \
+    --hash=sha256:4a7cd62e831afe623fbb7aabbb4fe583212115b3ef38a9f6b71869ba644624a2 \
+    --hash=sha256:4ba762ed58e8d68657fc1281e9bb72e1c3e79cc5d464be146e260c541ec12d84 \
+    --hash=sha256:4fc714bdbfb534f94034efaa6eadd74e5b93c8fa6315565a222f7b6f42ca1166 \
+    --hash=sha256:4ffa2ebd4c8530079140dd2d7f794a9d9a73cbb8e9d59ffe24c63436efa8f271 \
+    --hash=sha256:5a1504ad17ba4210df3a045132a7baeeba5a200e930f57512ee02909fc5c4cb5 \
+    --hash=sha256:5c364564d17da23db1106787675fc7af45f2f7b58b4173bfdd105564e132e6fb \
+    --hash=sha256:5e11661ce0fd30a6790e8bcdf263b9ec5988e95e63cf901972107efc49218b13 \
+    --hash=sha256:5f54b118ce5de9ac21c363d9b3caa6c800341e8c47a508787e5868c6b79c9323 \
+    --hash=sha256:5f5ff8d839f4566a474a969508fe1c5e59c31c80d9e140566f9a37bba7b8d556 \
+    --hash=sha256:61817945f2fe7d166e75fbfb28004034b48e44878177fc54d81688e7b85a3665 \
+    --hash=sha256:624e278a7d29b6445e4e813af92af37820fafb6dcc55c012c834f9e26f9aaaef \
+    --hash=sha256:63e46b3169866bd62849936de036f901a9356e36376079b05efa83caeaa02ceb \
+    --hash=sha256:6531b7ca5f951d663c339002e91aaebda765ec7d61b7d1e3991051906ddde119 \
+    --hash=sha256:68665f4c17edcceecc112dfed5dbe6f92261fb9d6054b47d01bf6371a6196126 \
+    --hash=sha256:696dd8d674d6ce621ab9d45b205df149399e4bb9aa34102c970b721554828510 \
+    --hash=sha256:6f783e0ec4803c787bcea93e13e9932edab72068f68ecffdf86a99fd5918878b \
+    --hash=sha256:723314c1d51722ab28bfcd5240d858512ffd3116449c557a1336cbe3919beb87 \
+    --hash=sha256:74b9127ffea03643e998e0c5ad9bd3811d3dac8c676e47db17b0ee7c3c3bf35f \
+    --hash=sha256:7530e201d10d7d14abce4fb54cfe5b94a0aefc87da539d0346a484ead376c3cc \
+    --hash=sha256:77733e3892bb0a7fa797826361ce8a9184d25c8dffaec60b7ffe928153680ba8 \
+    --hash=sha256:78ddaaa81421a29574a682b3179d4cf9e6d405a09b99d93ddcf7e5239c742e21 \
+    --hash=sha256:7c9129eb40958b3d4500fa2467e6a83356b3b61bfff1b414c7361d9220f9ae8f \
+    --hash=sha256:7d32706badfe136888bdea71c0def994644e09fff0bfe47441deaed8e96fdbc6 \
+    --hash=sha256:81965a16b675b35e1d09dd14df53f190f9129c0202356ed44ab2728b1c905658 \
+    --hash=sha256:8394d940e5d400d04cad4f75c0598665cbb81aecefaca82ca85bd28264af7f9b \
+    --hash=sha256:86d2f57d3e1379a9525c5ab067b27dbb8a0642fb5d454e17a9ac434f9ce523e3 \
+    --hash=sha256:883a91b5dd7d26492ff2f04f40fbb652de40fcc0afe07e8129e8ae779c2110eb \
+    --hash=sha256:88ad334a15b32a791ea935af224b9de1bf99bcd62fabf745d5f3442199d86d59 \
+    --hash=sha256:9261d3ce84fa1d38ed649c3638feefeae23d32ba9182963e465d58d62203bd24 \
+    --hash=sha256:97df63000f4fea395b2824da80e169731088656d1818a11b95f3b173747b6cd9 \
+    --hash=sha256:98d134c954828488b153d88ba1f34e14259284f256180ce659e8d83e9c05eaa3 \
+    --hash=sha256:996a38a83508c54c78a5f41456b0103c30508fed9abcad0a59b876d7398f25fd \
+    --hash=sha256:9a5bce9d23aac8f0cf0836ecfc033896aa8443b501c58d0602dbfd5bd5b37753 \
+    --hash=sha256:9a6b5099eeec78827553827f4c6b8615978bb4b6a88e5d9b93eddf8bb6790f55 \
+    --hash=sha256:9d18368b137c6295db49ce7218b1a9ba15c5bc254c96d7c9f9e924a9bc7825ad \
+    --hash=sha256:a4fa4fc04dff799089689f4fd502ce7d59de529fc2f40a2c8836886c03e0175a \
+    --hash=sha256:a5c7ba8ffb6d6f8f2ab08743be203654bb1aaa8c9dcb09f82ddd34eadb695605 \
+    --hash=sha256:aea443fffa9fbe3af1a9ba721a87f926fe548d32cab71d188a6ede77d0ff244e \
+    --hash=sha256:b10bd51f823d891193d4717448fab065733958bdb6a6b351967bd349d48d5c9b \
+    --hash=sha256:ba1a0996f6c2773bd83e63f18914c1de3c9dd26d55f4ac302a7efe93fb8e7433 \
+    --hash=sha256:bb2802e667b7051a1bebbfe93684841cc9351004e2badbd6411bf357ab8d5ac8 \
+    --hash=sha256:cfdd16ab5e59fc31b5e906d1a3f666571abc367598e3e02c83403acabc092e07 \
+    --hash=sha256:d06b0c8da4f16d1d1e352134427cb194a0a6e19ad5db9161bf32b2113409e728 \
+    --hash=sha256:d0776dea117cf5272382634bd2a5c1b6eb16767c223c6a5317cd3e2a757c61a0 \
+    --hash=sha256:d18ca8148bebe1b0a382a27a8ee60350091a6ddaf475fa05ef50dc35b5df6327 \
+    --hash=sha256:d4488a93b071c04dc20f5cecc3631fc78b9789dd72483ba15d423b5b3689b555 \
+    --hash=sha256:d5f7a395a8cf1621939692dba2a6b6a830efa6b3cee787d82c7de1ad2930de64 \
+    --hash=sha256:d7a80d21d613eec45e3d41eb22f8f94ddc758a6c4720842dc74c0581f54993d6 \
+    --hash=sha256:d97683ddee4723ae8c95d1eddac7c192e8c552da0c73a925a89fa8649bf13eea \
+    --hash=sha256:dcedcd19a557e182628afa1d553c3895a9f825b936415d0dbd3cd0bbcfd29b4b \
+    --hash=sha256:de6d1d1b9e5101508cb37ab0d972357cac5235f5c6533d1071964c47139257df \
+    --hash=sha256:df49e7a0861a8c36d089c1ed57d308623d60416dab2647a4a17fe050ba85de0e \
+    --hash=sha256:df933278128ea1cd77772673c73954e53a1c95a4fdf41eef97c2b779271bd0bd \
+    --hash=sha256:e08277a400de01bc72436a0ccd02bdf596631411f592ad985dcee21445bd0068 \
+    --hash=sha256:e38e63e6f3d1cec5a27e0afe90a085af8b6806ee208b33030e65b6516353f1a3 \
+    --hash=sha256:e55541f756f9b3ee346b840103f32779c695a19826a4c442b7954550a0972040 \
+    --hash=sha256:ec4e55f79b1c4ffb2eecd8a0cfba9955a2588497d96851f4c8f99aa4a1d39b12 \
+    --hash=sha256:ed1a53de42fbe34853ba90513cea21673481cd81ed1be739f7f2efb931b24916 \
+    --hash=sha256:ed541d70698978a20eb63d8c5d72f2cc6d7079d9d90f6b50bad07826f1320f5f \
+    --hash=sha256:f09e2ff1f17c2b51f2bc76d1cc33da96298f0a036a137f5440ab3ec5360b624f \
+    --hash=sha256:f220b0eea5965dec25480b6333c788fb72ce5f9129e8759ef876a1d805d00801 \
+    --hash=sha256:f3e0da4ebaef65158d4dfd7d3678aad692f7666877df0002b8a522cdf088f231 \
+    --hash=sha256:f455ee30a9d61d3e1a15abd5068827773d6e4dc513e795f380cdd59932c782d5 \
+    --hash=sha256:f5ef8f42bec47f21d07668a043f077d507e5bf4e668d5c6dfe6aaba89de1a5b8 \
+    --hash=sha256:f69a8e0b033b747bb3e36a44e7732f0c99f7edd5cea723d45bc0d6e95377ffee \
+    --hash=sha256:ff02b6d461a6de369f07ec15e465a88895f3223eb75073ffea56b84d9331f607
+    # via pydantic
 pygments==2.18.0 \
     --hash=sha256:786ff802f32e91311bff3889f6e9a86e81505fe99f2735bb6d60ae0c5004f199 \
     --hash=sha256:b8e6aca0523f3ab76fee51799c488e38782ac06eafcf95e7ba832985c8e7b13a
@@ -1414,6 +1869,8 @@
     --hash=sha256:37dd54208da7e1cd875388217d5e00ebd4179249f90fb72437e91a35459a0ad3 \
     --hash=sha256:a8b2bc7bffae282281c8140a97d3aa9c14da0b136dfe83f850eea9a5f7470427
     # via
+    #   aim
+    #   botocore
     #   ghp-import
     #   matplotlib
     #   pandas
@@ -1425,7 +1882,9 @@
 pytz==2024.1 \
     --hash=sha256:2a29735ea9c18baf14b448846bde5a48030ed267578472d8955cd0e7443a9812 \
     --hash=sha256:328171f4e3623139da4983451950b28e95ac706e13f3f2630a879749e7a8b319
-    # via pandas
+    # via
+    #   aim
+    #   pandas
 pyyaml==6.0.2 \
     --hash=sha256:01179a4a8559ab5de078078f37e5c1a30d76bb88519906844fd7bdea1b7729ff \
     --hash=sha256:0833f8694549e586547b576dcfaba4a6b55b9e96098b36cdc7ebefe667dfed48 \
@@ -1534,14 +1993,23 @@
     --hash=sha256:70761cfe03c773ceb22aa2f671b4757976145175cdfca038c02654d061d6dcc6
     # via
     #   -r tools/python/requirements.txt
+    #   aim
     #   tensorflow
     #   tensorflow-datasets
+restrictedpython==7.2 \
+    --hash=sha256:139cb41da6e57521745a566d05825f7a09e6a884f7fa922568cff0a70b84ce6b \
+    --hash=sha256:4d1d30f709a6621ca7c4236f08b67b732a651c8099145f137078c7dd4bed3d21
+    # via aim
 rich==13.8.0 \
     --hash=sha256:2e85306a063b9492dffc86278197a60cbece75bcb766022f3436f567cae11bdc \
     --hash=sha256:a5ac1f1cd448ade0d59cc3356f7db7a7ccda2c8cbae9c7a90c28ff463d3e91f4
     # via
     #   flax
     #   keras
+s3transfer==0.10.2 \
+    --hash=sha256:0711534e9356d3cc692fdde846b4a1e4b0cb6519971860796e6bc4c7aea00ef6 \
+    --hash=sha256:eca1c20de70a39daee580aef4986996620f365c4e0fda6a86100231d62f1bf69
+    # via boto3
 scipy==1.13.1 \
     --hash=sha256:017367484ce5498445aade74b1d5ab377acdc65e27095155e448c88497755a5d \
     --hash=sha256:095a87a0312b08dfd6a6155cbbd310a8c51800fc931b8c0b84003014b874ed3c \
@@ -1630,6 +2098,68 @@
     #   python-dateutil
     #   tensorboard
     #   tensorflow
+    #   tensorflow-probability
+sniffio==1.3.1 \
+    --hash=sha256:2f6da418d1f1e0fddd844478f41680e794e6051915791a034ff65e5f100525a2 \
+    --hash=sha256:f4324edc670a0f49750a81b895f35c3adb843cca46f0530f79fc1babb23789dc
+    # via anyio
+sqlalchemy==2.0.35 \
+    --hash=sha256:016b2e665f778f13d3c438651dd4de244214b527a275e0acf1d44c05bc6026a9 \
+    --hash=sha256:032d979ce77a6c2432653322ba4cbeabf5a6837f704d16fa38b5a05d8e21fa00 \
+    --hash=sha256:0375a141e1c0878103eb3d719eb6d5aa444b490c96f3fedab8471c7f6ffe70ee \
+    --hash=sha256:042622a5306c23b972192283f4e22372da3b8ddf5f7aac1cc5d9c9b222ab3ff6 \
+    --hash=sha256:05c3f58cf91683102f2f0265c0db3bd3892e9eedabe059720492dbaa4f922da1 \
+    --hash=sha256:0630774b0977804fba4b6bbea6852ab56c14965a2b0c7fc7282c5f7d90a1ae72 \
+    --hash=sha256:0f9f3f9a3763b9c4deb8c5d09c4cc52ffe49f9876af41cc1b2ad0138878453cf \
+    --hash=sha256:1b56961e2d31389aaadf4906d453859f35302b4eb818d34a26fab72596076bb8 \
+    --hash=sha256:22b83aed390e3099584b839b93f80a0f4a95ee7f48270c97c90acd40ee646f0b \
+    --hash=sha256:25b0f63e7fcc2a6290cb5f7f5b4fc4047843504983a28856ce9b35d8f7de03cc \
+    --hash=sha256:2a275a806f73e849e1c309ac11108ea1a14cd7058577aba962cd7190e27c9e3c \
+    --hash=sha256:2ab3f0336c0387662ce6221ad30ab3a5e6499aab01b9790879b6578fd9b8faa1 \
+    --hash=sha256:2e795c2f7d7249b75bb5f479b432a51b59041580d20599d4e112b5f2046437a3 \
+    --hash=sha256:3655af10ebcc0f1e4e06c5900bb33e080d6a1fa4228f502121f28a3b1753cde5 \
+    --hash=sha256:4668bd8faf7e5b71c0319407b608f278f279668f358857dbfd10ef1954ac9f90 \
+    --hash=sha256:4c31943b61ed8fdd63dfd12ccc919f2bf95eefca133767db6fbbd15da62078ec \
+    --hash=sha256:4fdcd72a789c1c31ed242fd8c1bcd9ea186a98ee8e5408a50e610edfef980d71 \
+    --hash=sha256:627dee0c280eea91aed87b20a1f849e9ae2fe719d52cbf847c0e0ea34464b3f7 \
+    --hash=sha256:67219632be22f14750f0d1c70e62f204ba69d28f62fd6432ba05ab295853de9b \
+    --hash=sha256:6921ee01caf375363be5e9ae70d08ce7ca9d7e0e8983183080211a062d299468 \
+    --hash=sha256:69683e02e8a9de37f17985905a5eca18ad651bf592314b4d3d799029797d0eb3 \
+    --hash=sha256:6a93c5a0dfe8d34951e8a6f499a9479ffb9258123551fa007fc708ae2ac2bc5e \
+    --hash=sha256:732e026240cdd1c1b2e3ac515c7a23820430ed94292ce33806a95869c46bd139 \
+    --hash=sha256:7befc148de64b6060937231cbff8d01ccf0bfd75aa26383ffdf8d82b12ec04ff \
+    --hash=sha256:890da8cd1941fa3dab28c5bac3b9da8502e7e366f895b3b8e500896f12f94d11 \
+    --hash=sha256:89b64cd8898a3a6f642db4eb7b26d1b28a497d4022eccd7717ca066823e9fb01 \
+    --hash=sha256:8a6219108a15fc6d24de499d0d515c7235c617b2540d97116b663dade1a54d62 \
+    --hash=sha256:8cdf1a0dbe5ced887a9b127da4ffd7354e9c1a3b9bb330dce84df6b70ccb3a8d \
+    --hash=sha256:8d625eddf7efeba2abfd9c014a22c0f6b3796e0ffb48f5d5ab106568ef01ff5a \
+    --hash=sha256:93a71c8601e823236ac0e5d087e4f397874a421017b3318fd92c0b14acf2b6db \
+    --hash=sha256:9509c4123491d0e63fb5e16199e09f8e262066e58903e84615c301dde8fa2e87 \
+    --hash=sha256:a29762cd3d116585278ffb2e5b8cc311fb095ea278b96feef28d0b423154858e \
+    --hash=sha256:a62dd5d7cc8626a3634208df458c5fe4f21200d96a74d122c83bc2015b333bc1 \
+    --hash=sha256:ada603db10bb865bbe591939de854faf2c60f43c9b763e90f653224138f910d9 \
+    --hash=sha256:aee110e4ef3c528f3abbc3c2018c121e708938adeeff9006428dd7c8555e9b3f \
+    --hash=sha256:b76d63495b0508ab9fc23f8152bac63205d2a704cd009a2b0722f4c8e0cba8e0 \
+    --hash=sha256:c0d8326269dbf944b9201911b0d9f3dc524d64779a07518199a58384c3d37a44 \
+    --hash=sha256:c41411e192f8d3ea39ea70e0fae48762cd11a2244e03751a98bd3c0ca9a4e936 \
+    --hash=sha256:c68fe3fcde03920c46697585620135b4ecfdfc1ed23e75cc2c2ae9f8502c10b8 \
+    --hash=sha256:cb8bea573863762bbf45d1e13f87c2d2fd32cee2dbd50d050f83f87429c9e1ea \
+    --hash=sha256:cc32b2990fc34380ec2f6195f33a76b6cdaa9eecf09f0c9404b74fc120aef36f \
+    --hash=sha256:ccae5de2a0140d8be6838c331604f91d6fafd0735dbdcee1ac78fc8fbaba76b4 \
+    --hash=sha256:d299797d75cd747e7797b1b41817111406b8b10a4f88b6e8fe5b5e59598b43b0 \
+    --hash=sha256:e04b622bb8a88f10e439084486f2f6349bf4d50605ac3e445869c7ea5cf0fa8c \
+    --hash=sha256:e11d7ea4d24f0a262bccf9a7cd6284c976c5369dac21db237cff59586045ab9f \
+    --hash=sha256:e21f66748ab725ade40fa7af8ec8b5019c68ab00b929f6643e1b1af461eddb60 \
+    --hash=sha256:eb60b026d8ad0c97917cb81d3662d0b39b8ff1335e3fabb24984c6acd0c900a2 \
+    --hash=sha256:f021d334f2ca692523aaf7bbf7592ceff70c8594fad853416a81d66b35e3abf9 \
+    --hash=sha256:f552023710d4b93d8fb29a91fadf97de89c5926c6bd758897875435f2a939f33
+    # via
+    #   aim
+    #   alembic
+starlette==0.38.6 \
+    --hash=sha256:4517a1409e2e73ee4951214ba012052b9e16f60e90d73cfb06192c19203bbb05 \
+    --hash=sha256:863a1588f5574e70a821dadefb41e4881ea451a47a3cd1b4df359d4ffefe5ead
+    # via fastapi
 sympy==1.13.2 \
     --hash=sha256:401449d84d07be9d0c7a46a64bd54fe097667d5e7181bfe67ec777be9e01cb13 \
     --hash=sha256:c51d75517712f1aed280d4ce58506a4a88d635d6b5dd48b39102a7ae1f3fcfe9
@@ -1638,6 +2168,10 @@
     --hash=sha256:0095b12bf5966de529c0feb1fa08671671b3368eec77d7ef7ab114be2c068b3c \
     --hash=sha256:024ca478df22e9340661486f85298cff5f6dcdba14f3813e8830015b9ed1948f
     # via -r tools/python/requirements.txt
+tenacity==9.0.0 \
+    --hash=sha256:807f37ca97d62aa361264d497b0e31e92b8027044942bfa756160d908320d73b \
+    --hash=sha256:93de0c98785b27fcf659856aa9f54bfbd399e29969b0621bc7f762bd441b4539
+    # via plotly
 tensorboard==2.17.1 \
     --hash=sha256:253701a224000eeca01eee6f7e978aea7b408f60b91eb0babdb04e78947b773e
     # via tensorflow
@@ -1663,7 +2197,9 @@
     --hash=sha256:e8d26d6c24ccfb139db1306599257ca8f5cfe254ef2d023bfb667f374a17a64d \
     --hash=sha256:ee18b4fcd627c5e872eabb25092af6c808b6ec77948662c88fc5c89a60eb0211 \
     --hash=sha256:ef615c133cf4d592a073feda634ccbeb521a554be57de74f8c318d38febbeab5
-    # via -r tools/python/requirements.txt
+    # via
+    #   -r tools/python/requirements.txt
+    #   tf-keras
 tensorflow-datasets==4.9.3 \
     --hash=sha256:09cd60eccab0d5a9d15f53e76ee0f1b530ee5aa3665e42be621a4810d9fa5db6 \
     --hash=sha256:90390077dde2c9e4e240754ddfc5bb50b482946d421c8a34677c3afdb0463427
@@ -1689,6 +2225,9 @@
 tensorflow-metadata==1.15.0 \
     --hash=sha256:cb84d8e159128aeae7b3f6013ccd7969c69d2e6d1a7b255dbfa6f5344d962986
     # via tensorflow-datasets
+tensorflow-probability==0.24.0 \
+    --hash=sha256:8c1774683e38359dbcaf3697e79b7e6a4e69b9c7b3679e78ee18f43e59e5759b
+    # via -r tools/python/requirements.txt
 tensorstore==0.1.64 \
     --hash=sha256:1a78aedbddccc09ea283b145496da03dbc7eb8693ae4e01074ed791d72b7eac2 \
     --hash=sha256:24a4cebaf9d0e75d494342948f68edc971d6bb90e23192ddf8d98397fb1ff3cb \
@@ -1721,6 +2260,10 @@
     # via
     #   tensorflow
     #   tensorflow-datasets
+tf-keras==2.17.0 \
+    --hash=sha256:cc97717e4dc08487f327b0740a984043a9e0123c7a4e21206711669d3ec41c88 \
+    --hash=sha256:fda97c18da30da0f72a5a7e80f3eee343b09f4c206dad6c57c944fb2cd18560e
+    # via -r tools/python/requirements.txt
 toml==0.10.2 \
     --hash=sha256:806143ae5bfb6a3c6e736a764057db0e6a0e05e338b5630894a5f779cabb4f9b \
     --hash=sha256:b3bda1d108d5dd99f4a20d24d9c348e91c4db7ab1b749200bded2f839ccbe68f
@@ -1749,7 +2292,9 @@
 tqdm==4.66.5 \
     --hash=sha256:90279a3770753eafc9194a0364852159802111925aa30eb3f9d85b0e805ac7cd \
     --hash=sha256:e1020aef2e5096702d8a025ac7d16b1577279c9d63f8375b63083e9a5f0fcbad
-    # via tensorflow-datasets
+    # via
+    #   aim
+    #   tensorflow-datasets
 typeguard==2.13.3 \
     --hash=sha256:00edaa8da3a133674796cf5ea87d9f4b4c367d77476e185e80251cc13dfbb8c4 \
     --hash=sha256:5e3e3be01e887e7eafae5af63d1f36c849aaa94e3a0112097312aabfa16284f1
@@ -1758,22 +2303,36 @@
     --hash=sha256:04e5ca0351e0f3f85c6853954072df659d0d13fac324d0072316b67d7794700d \
     --hash=sha256:1a7ead55c7e559dd4dee8856e3a88b41225abfe1ce8df57b7c13915fe121ffb8
     # via
+    #   alembic
+    #   anyio
     #   chex
     #   clu
     #   etils
+    #   fastapi
     #   flashbax
     #   flax
     #   optree
     #   orbax-checkpoint
+    #   pydantic
+    #   pydantic-core
+    #   sqlalchemy
+    #   starlette
     #   tensorflow
+    #   uvicorn
 tzdata==2024.1 \
     --hash=sha256:2674120f8d891909751c38abcdfd386ac0a5a1127954fbc332af6b5ceae07efd \
     --hash=sha256:9068bc196136463f5245e51efda838afa15aaeca9903f49050dfa2679db4d252
     # via pandas
-urllib3==2.2.2 \
-    --hash=sha256:a448b2f64d686155468037e1ace9f2d2199776e17f0a46610480d311f73e3472 \
-    --hash=sha256:dd505485549a7a552833da5e6063639d0d177c04f23bc3864e41e5dc5f612168
-    # via requests
+urllib3==1.26.20 \
+    --hash=sha256:0ed14ccfbf1c30a9072c7ca157e4319b70d65f623e91e7b32fadb2853431016e \
+    --hash=sha256:40c2dc0c681e47eb8f90e7e27bf6ff7df2e677421fd46756da1161c39ca70d32
+    # via
+    #   botocore
+    #   requests
+uvicorn==0.30.6 \
+    --hash=sha256:4b15decdda1e72be08209e860a1e10e92439ad5b97cf44cc945fcbee66fc5788 \
+    --hash=sha256:65fd46fe3fda5bdc1b03b94eb634923ff18cd35b2f084813ea79d1f103f711b5
+    # via aim
 validators==0.34.0 \
     --hash=sha256:647fe407b45af9a74d245b943b18e6a816acf4926974278f6dd617778e1e781f \
     --hash=sha256:c804b476e3e6d3786fa07a30073a4ef694e617805eb1946ceee3fe5a9b8b1321
@@ -1810,6 +2369,94 @@
     --hash=sha256:f8b2918c19e0d48f5f20df458c84692e2a054f02d9df25e6c3c930063eca64c1 \
     --hash=sha256:fb223456db6e5f7bd9bbd5cd969f05aae82ae21acc00643b60d81c770abd402b
     # via mkdocs
+websockets==13.1 \
+    --hash=sha256:004280a140f220c812e65f36944a9ca92d766b6cc4560be652a0a3883a79ed8a \
+    --hash=sha256:035233b7531fb92a76beefcbf479504db8c72eb3bff41da55aecce3a0f729e54 \
+    --hash=sha256:149e622dc48c10ccc3d2760e5f36753db9cacf3ad7bc7bbbfd7d9c819e286f23 \
+    --hash=sha256:163e7277e1a0bd9fb3c8842a71661ad19c6aa7bb3d6678dc7f89b17fbcc4aeb7 \
+    --hash=sha256:18503d2c5f3943e93819238bf20df71982d193f73dcecd26c94514f417f6b135 \
+    --hash=sha256:1971e62d2caa443e57588e1d82d15f663b29ff9dfe7446d9964a4b6f12c1e700 \
+    --hash=sha256:204e5107f43095012b00f1451374693267adbb832d29966a01ecc4ce1db26faf \
+    --hash=sha256:2510c09d8e8df777177ee3d40cd35450dc169a81e747455cc4197e63f7e7bfe5 \
+    --hash=sha256:25c35bf84bf7c7369d247f0b8cfa157f989862c49104c5cf85cb5436a641d93e \
+    --hash=sha256:2f85cf4f2a1ba8f602298a853cec8526c2ca42a9a4b947ec236eaedb8f2dc80c \
+    --hash=sha256:308e20f22c2c77f3f39caca508e765f8725020b84aa963474e18c59accbf4c02 \
+    --hash=sha256:325b1ccdbf5e5725fdcb1b0e9ad4d2545056479d0eee392c291c1bf76206435a \
+    --hash=sha256:327b74e915cf13c5931334c61e1a41040e365d380f812513a255aa804b183418 \
+    --hash=sha256:346bee67a65f189e0e33f520f253d5147ab76ae42493804319b5716e46dddf0f \
+    --hash=sha256:38377f8b0cdeee97c552d20cf1865695fcd56aba155ad1b4ca8779a5b6ef4ac3 \
+    --hash=sha256:3c78383585f47ccb0fcf186dcb8a43f5438bd7d8f47d69e0b56f71bf431a0a68 \
+    --hash=sha256:4059f790b6ae8768471cddb65d3c4fe4792b0ab48e154c9f0a04cefaabcd5978 \
+    --hash=sha256:459bf774c754c35dbb487360b12c5727adab887f1622b8aed5755880a21c4a20 \
+    --hash=sha256:463e1c6ec853202dd3657f156123d6b4dad0c546ea2e2e38be2b3f7c5b8e7295 \
+    --hash=sha256:4676df3fe46956fbb0437d8800cd5f2b6d41143b6e7e842e60554398432cf29b \
+    --hash=sha256:485307243237328c022bc908b90e4457d0daa8b5cf4b3723fd3c4a8012fce4c6 \
+    --hash=sha256:48a2ef1381632a2f0cb4efeff34efa97901c9fbc118e01951ad7cfc10601a9bb \
+    --hash=sha256:4b889dbd1342820cc210ba44307cf75ae5f2f96226c0038094455a96e64fb07a \
+    --hash=sha256:586a356928692c1fed0eca68b4d1c2cbbd1ca2acf2ac7e7ebd3b9052582deefa \
+    --hash=sha256:58cf7e75dbf7e566088b07e36ea2e3e2bd5676e22216e4cad108d4df4a7402a0 \
+    --hash=sha256:5993260f483d05a9737073be197371940c01b257cc45ae3f1d5d7adb371b266a \
+    --hash=sha256:5dd6da9bec02735931fccec99d97c29f47cc61f644264eb995ad6c0c27667238 \
+    --hash=sha256:5f2e75431f8dc4a47f31565a6e1355fb4f2ecaa99d6b89737527ea917066e26c \
+    --hash=sha256:5f9fee94ebafbc3117c30be1844ed01a3b177bb6e39088bc6b2fa1dc15572084 \
+    --hash=sha256:61fc0dfcda609cda0fc9fe7977694c0c59cf9d749fbb17f4e9483929e3c48a19 \
+    --hash=sha256:624459daabeb310d3815b276c1adef475b3e6804abaf2d9d2c061c319f7f187d \
+    --hash=sha256:62d516c325e6540e8a57b94abefc3459d7dab8ce52ac75c96cad5549e187e3a7 \
+    --hash=sha256:6548f29b0e401eea2b967b2fdc1c7c7b5ebb3eeb470ed23a54cd45ef078a0db9 \
+    --hash=sha256:6d2aad13a200e5934f5a6767492fb07151e1de1d6079c003ab31e1823733ae79 \
+    --hash=sha256:6d6855bbe70119872c05107e38fbc7f96b1d8cb047d95c2c50869a46c65a8e96 \
+    --hash=sha256:70c5be9f416aa72aab7a2a76c90ae0a4fe2755c1816c153c1a2bcc3333ce4ce6 \
+    --hash=sha256:730f42125ccb14602f455155084f978bd9e8e57e89b569b4d7f0f0c17a448ffe \
+    --hash=sha256:7a43cfdcddd07f4ca2b1afb459824dd3c6d53a51410636a2c7fc97b9a8cf4842 \
+    --hash=sha256:7bd6abf1e070a6b72bfeb71049d6ad286852e285f146682bf30d0296f5fbadfa \
+    --hash=sha256:7c1e90228c2f5cdde263253fa5db63e6653f1c00e7ec64108065a0b9713fa1b3 \
+    --hash=sha256:7c65ffa900e7cc958cd088b9a9157a8141c991f8c53d11087e6fb7277a03f81d \
+    --hash=sha256:80c421e07973a89fbdd93e6f2003c17d20b69010458d3a8e37fb47874bd67d51 \
+    --hash=sha256:82d0ba76371769d6a4e56f7e83bb8e81846d17a6190971e38b5de108bde9b0d7 \
+    --hash=sha256:83f91d8a9bb404b8c2c41a707ac7f7f75b9442a0a876df295de27251a856ad09 \
+    --hash=sha256:87c6e35319b46b99e168eb98472d6c7d8634ee37750d7693656dc766395df096 \
+    --hash=sha256:8d23b88b9388ed85c6faf0e74d8dec4f4d3baf3ecf20a65a47b836d56260d4b9 \
+    --hash=sha256:9156c45750b37337f7b0b00e6248991a047be4aa44554c9886fe6bdd605aab3b \
+    --hash=sha256:91a0fa841646320ec0d3accdff5b757b06e2e5c86ba32af2e0815c96c7a603c5 \
+    --hash=sha256:95858ca14a9f6fa8413d29e0a585b31b278388aa775b8a81fa24830123874678 \
+    --hash=sha256:95df24ca1e1bd93bbca51d94dd049a984609687cb2fb08a7f2c56ac84e9816ea \
+    --hash=sha256:9b37c184f8b976f0c0a231a5f3d6efe10807d41ccbe4488df8c74174805eea7d \
+    --hash=sha256:9b6f347deb3dcfbfde1c20baa21c2ac0751afaa73e64e5b693bb2b848efeaa49 \
+    --hash=sha256:9d75baf00138f80b48f1eac72ad1535aac0b6461265a0bcad391fc5aba875cfc \
+    --hash=sha256:9ef8aa8bdbac47f4968a5d66462a2a0935d044bf35c0e5a8af152d58516dbeb5 \
+    --hash=sha256:a11e38ad8922c7961447f35c7b17bffa15de4d17c70abd07bfbe12d6faa3e027 \
+    --hash=sha256:a1b54689e38d1279a51d11e3467dd2f3a50f5f2e879012ce8f2d6943f00e83f0 \
+    --hash=sha256:a3b3366087c1bc0a2795111edcadddb8b3b59509d5db5d7ea3fdd69f954a8878 \
+    --hash=sha256:a569eb1b05d72f9bce2ebd28a1ce2054311b66677fcd46cf36204ad23acead8c \
+    --hash=sha256:a7affedeb43a70351bb811dadf49493c9cfd1ed94c9c70095fd177e9cc1541fa \
+    --hash=sha256:a9a396a6ad26130cdae92ae10c36af09d9bfe6cafe69670fd3b6da9b07b4044f \
+    --hash=sha256:a9ab1e71d3d2e54a0aa646ab6d4eebfaa5f416fe78dfe4da2839525dc5d765c6 \
+    --hash=sha256:a9cd1af7e18e5221d2878378fbc287a14cd527fdd5939ed56a18df8a31136bb2 \
+    --hash=sha256:a9dcaf8b0cc72a392760bb8755922c03e17a5a54e08cca58e8b74f6902b433cf \
+    --hash=sha256:b9d7439d7fab4dce00570bb906875734df13d9faa4b48e261c440a5fec6d9708 \
+    --hash=sha256:bcc03c8b72267e97b49149e4863d57c2d77f13fae12066622dc78fe322490fe6 \
+    --hash=sha256:c11d4d16e133f6df8916cc5b7e3e96ee4c44c936717d684a94f48f82edb7c92f \
+    --hash=sha256:c1dca61c6db1166c48b95198c0b7d9c990b30c756fc2923cc66f68d17dc558fd \
+    --hash=sha256:c518e84bb59c2baae725accd355c8dc517b4a3ed8db88b4bc93c78dae2974bf2 \
+    --hash=sha256:c7934fd0e920e70468e676fe7f1b7261c1efa0d6c037c6722278ca0228ad9d0d \
+    --hash=sha256:c7e72ce6bda6fb9409cc1e8164dd41d7c91466fb599eb047cfda72fe758a34a7 \
+    --hash=sha256:c90d6dec6be2c7d03378a574de87af9b1efea77d0c52a8301dd831ece938452f \
+    --hash=sha256:ceec59f59d092c5007e815def4ebb80c2de330e9588e101cf8bd94c143ec78a5 \
+    --hash=sha256:cf1781ef73c073e6b0f90af841aaf98501f975d306bbf6221683dd594ccc52b6 \
+    --hash=sha256:d04f13a1d75cb2b8382bdc16ae6fa58c97337253826dfe136195b7f89f661557 \
+    --hash=sha256:d6d300f8ec35c24025ceb9b9019ae9040c1ab2f01cddc2bcc0b518af31c75c14 \
+    --hash=sha256:d8dbb1bf0c0a4ae8b40bdc9be7f644e2f3fb4e8a9aca7145bfa510d4a374eeb7 \
+    --hash=sha256:de58647e3f9c42f13f90ac7e5f58900c80a39019848c5547bc691693098ae1bd \
+    --hash=sha256:deeb929efe52bed518f6eb2ddc00cc496366a14c726005726ad62c2dd9017a3c \
+    --hash=sha256:df01aea34b6e9e33572c35cd16bae5a47785e7d5c8cb2b54b2acdb9678315a17 \
+    --hash=sha256:e2620453c075abeb0daa949a292e19f56de518988e079c36478bacf9546ced23 \
+    --hash=sha256:e4450fc83a3df53dec45922b576e91e94f5578d06436871dce3a6be38e40f5db \
+    --hash=sha256:e54affdeb21026329fb0744ad187cf812f7d3c2aa702a5edb562b325191fcab6 \
+    --hash=sha256:e9875a0143f07d74dc5e1ded1c4581f0d9f7ab86c78994e2ed9e95050073c94d \
+    --hash=sha256:f1c3cf67185543730888b20682fb186fc8d0fa6f07ccc3ef4390831ab4b388d9 \
+    --hash=sha256:f48c749857f8fb598fb890a75f540e3221d0976ed0bf879cf3c7eef34151acee \
+    --hash=sha256:f779498eeec470295a2b1a5d97aa1bc9814ecd25e1eb637bd9d1c73a327387f6
+    # via aim
 werkzeug==3.0.4 \
     --hash=sha256:02c9eb92b7d6c06f31a782811505d2157837cea66aaede3e217c7c27c039476c \
     --hash=sha256:34f2371506b250df4d4f84bfe7b0921e4762525762bbd936614909fe25cd7306
diff --git a/tools/python/requirements.txt b/tools/python/requirements.txt
index 2b806f5..342d8ab 100644
--- a/tools/python/requirements.txt
+++ b/tools/python/requirements.txt
@@ -41,6 +41,12 @@
 
 tensorflow
 tensorflow_datasets
+tensorflow_probability
+tf_keras
 
 # Experience buffer for reinforcement learning
 flashbax
+
+# Experiment tracking
+aim
+plotly
diff --git a/tools/python/runtime_binary.sh b/tools/python/runtime_binary.sh
index 8498408..95283e0 100755
--- a/tools/python/runtime_binary.sh
+++ b/tools/python/runtime_binary.sh
@@ -27,6 +27,9 @@
     LD_LIBRARY_PATH+=":${path}/../gtk_runtime/lib/x86_64-linux-gnu"
     LD_LIBRARY_PATH+=":${path}/../gtk_runtime/usr/lib/x86_64-linux-gnu"
     LD_LIBRARY_PATH+=":${path}/../gtk_runtime/usr/lib"
+    if [[ -e "${path}/../pip_deps_nvidia_nccl_cu12" ]]; then
+      LD_LIBRARY_PATH+=":${path}/../pip_deps_nvidia_nccl_cu12/site-packages/nvidia/nccl/lib/"
+    fi
     export LD_LIBRARY_PATH
     break
   fi
diff --git a/tools/python/whl_overrides.json b/tools/python/whl_overrides.json
index 586a9d3..c27c8ac 100644
--- a/tools/python/whl_overrides.json
+++ b/tools/python/whl_overrides.json
@@ -3,6 +3,38 @@
         "sha256": "526a04eadab8b4ee719ce68f204172ead1027549089702d99b9059f129ff1308",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/absl_py-2.1.0-py3-none-any.whl"
     },
+    "aim==3.24.0": {
+        "sha256": "1789bcc9edf69ae90bb18a6f3fa4862095b8020eadc7e5e0e93ba4f242250947",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/aim-3.24.0-cp39-cp39-manylinux_2_28_x86_64.whl"
+    },
+    "aim_ui==3.24.0": {
+        "sha256": "b62fbcb0ea4b036b99985d4c649220cdbe4523f05408dcb2324ffc7e4539f321",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/aim_ui-3.24.0-py3-none-any.whl"
+    },
+    "aimrecords==0.0.7": {
+        "sha256": "b9276890891c5fd68f817e20fc5d466a80c01e22fa468eaa979331448a75d601",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/aimrecords-0.0.7-py2.py3-none-any.whl"
+    },
+    "aimrocks==0.5.2": {
+        "sha256": "e6a79076d669dbf221442399da893baff6c1549031edbb5d556042d1b9b6525c",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/aimrocks-0.5.2-cp39-cp39-manylinux_2_24_x86_64.whl"
+    },
+    "aiofiles==24.1.0": {
+        "sha256": "b4ec55f4195e3eb5d7abd1bf7e061763e864dd4954231fb8539a0ef8bb8260e5",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/aiofiles-24.1.0-py3-none-any.whl"
+    },
+    "alembic==1.13.3": {
+        "sha256": "908e905976d15235fae59c9ac42c4c5b75cfcefe3d27c0fbf7ae15a37715d80e",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/alembic-1.13.3-py3-none-any.whl"
+    },
+    "annotated_types==0.7.0": {
+        "sha256": "1f02e8b43a8fbbc3f3e0d4f0f4bfc8131bcb4eebe8849b8e5c773f3a1c582a53",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/annotated_types-0.7.0-py3-none-any.whl"
+    },
+    "anyio==4.6.0": {
+        "sha256": "c7d2e9d63e31599eeb636c8c5c03a7e108d73b345f064f1c19fdc87b79036a9a",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/anyio-4.6.0-py3-none-any.whl"
+    },
     "array_record==0.5.1": {
         "sha256": "9922862216a9d3be76fdc27968af1ec0ea20f986329998ba45b0f01ee3e646fa",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/array_record-0.5.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
@@ -11,6 +43,10 @@
         "sha256": "c2652417f2c8b5bb325c885ae329bdf3f86424075c4fd1a128674bc6fba4b8e8",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/astunparse-1.6.3-py2.py3-none-any.whl"
     },
+    "base58==2.0.1": {
+        "sha256": "447adc750d6b642987ffc6d397ecd15a799852d5f6a1d308d384500243825058",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/base58-2.0.1-py3-none-any.whl"
+    },
     "blinker==1.8.2": {
         "sha256": "1779309f71bf239144b9399d06ae925637cf6634cf6bd131104184531bf67c01",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/blinker-1.8.2-py3-none-any.whl"
@@ -19,6 +55,18 @@
         "sha256": "c6f33817f866fc67fbeb5df79cd13a8bb592c05c591f3fd7f4f22b824f7afa01",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/bokeh-3.4.3-py3-none-any.whl"
     },
+    "boto3==1.35.27": {
+        "sha256": "3da139ca038032e92086e26d23833b557f0c257520162bfd3d6f580bf8032c86",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/boto3-1.35.27-py3-none-any.whl"
+    },
+    "botocore==1.35.27": {
+        "sha256": "c299c70b5330a8634e032883ce8a72c2c6d9fdbc985d8191199cb86b92e7cbbd",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/botocore-1.35.27-py3-none-any.whl"
+    },
+    "cachetools==5.5.0": {
+        "sha256": "02134e8439cdc2ffb62023ce1debca2944c3f289d66bb17ead3ab3dede74b292",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/cachetools-5.5.0-py3-none-any.whl"
+    },
     "casadi==3.6.6": {
         "sha256": "cc3594b348f306018b142638d0a8c4026f80e996b4e9798fc504899256a7b029",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/casadi-3.6.6-cp39-none-manylinux2014_x86_64.whl"
@@ -27,6 +75,10 @@
         "sha256": "922820b53db7a7257ffbda3f597266d435245903d80737e34f8a45ff3e3230d8",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/certifi-2024.8.30-py3-none-any.whl"
     },
+    "cffi==1.17.1": {
+        "sha256": "cdf5ce3acdfd1661132f2a9c19cac174758dc2352bfe37d98aa7512c6b7178b3",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/cffi-1.17.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+    },
     "charset_normalizer==3.3.2": {
         "sha256": "b261ccdec7821281dade748d088bb6e9b69e6d15b30652b74cbbac25e280b796",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/charset_normalizer-3.3.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
@@ -39,6 +91,10 @@
         "sha256": "ae74fb96c20a0277a1d615f1e4d73c8414f5a98db8b799a7931d1582f3390c28",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/click-8.1.7-py3-none-any.whl"
     },
+    "cloudpickle==3.1.0": {
+        "sha256": "fe11acda67f61aaaec473e3afe030feb131d78a43461b718185363384f1ba12e",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/cloudpickle-3.1.0-py3-none-any.whl"
+    },
     "clu==0.0.12": {
         "sha256": "0d183e7d25f7dd0700444510a264e24700e2f068bdabd199ed22866f7e54edba",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/clu-0.0.12-py3-none-any.whl"
@@ -51,10 +107,18 @@
         "sha256": "68a32389b06b82c2fdd68276148d7b9275b5f5cf13e5417e4252f6d1a34f72a2",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/contourpy-1.3.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
     },
+    "cryptography==43.0.1": {
+        "sha256": "511f4273808ab590912a93ddb4e3914dfd8a388fed883361b02dea3791f292e1",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/cryptography-43.0.1-cp39-abi3-manylinux_2_28_x86_64.whl"
+    },
     "cycler==0.12.1": {
         "sha256": "85cef7cff222d8644161529808465972e51340599459b8ac3ccbac5a854e0d30",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/cycler-0.12.1-py3-none-any.whl"
     },
+    "decorator==5.1.1": {
+        "sha256": "b8c3f85900b9dc423225913c5aace94729fe1fa9763b38939a95226f02d37186",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/decorator-5.1.1-py3-none-any.whl"
+    },
     "dm_tree==0.1.8": {
         "sha256": "181c35521d480d0365f39300542cb6cd7fd2b77351bb43d7acfda15aef63b317",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/dm_tree-0.1.8-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
@@ -63,6 +127,18 @@
         "sha256": "6dc882d355e1e98a5d1a148d6323679dc47c9a5792939b9de72615aa4737eb0b",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/etils-1.5.2-py3-none-any.whl"
     },
+    "exceptiongroup==1.2.2": {
+        "sha256": "3111b9d131c238bec2f8f516e123e14ba243563fb135d3fe885990585aa7795b",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/exceptiongroup-1.2.2-py3-none-any.whl"
+    },
+    "fastapi==0.115.0": {
+        "sha256": "17ea427674467486e997206a5ab25760f6b09e069f099b96f5b55a32fb6f1631",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/fastapi-0.115.0-py3-none-any.whl"
+    },
+    "filelock==3.16.1": {
+        "sha256": "2082e5703d51fbf98ea75855d9d5527e33d8ff23099bec374a134febee6946b0",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/filelock-3.16.1-py3-none-any.whl"
+    },
     "flashbax==0.1.2": {
         "sha256": "ac50b2580808ce63787da0ae240db14986e3404ade98a33335e6d7a5efe84859",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/flashbax-0.1.2-py3-none-any.whl"
@@ -103,10 +179,18 @@
         "sha256": "b32482794a366b5366a32c92a9a9201b107821889935a02b3e51f6b432ea84ed",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/google_pasta-0.2.0-py3-none-any.whl"
     },
+    "greenlet==3.1.1": {
+        "sha256": "63e4844797b975b9af3a3fb8f7866ff08775f5426925e1e0bbcfe7932059a12c",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/greenlet-3.1.1-cp39-cp39-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl"
+    },
     "grpcio==1.66.1": {
         "sha256": "48b0d92d45ce3be2084b92fb5bae2f64c208fea8ceed7fccf6a7b524d3c4942e",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/grpcio-1.66.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
     },
+    "h11==0.14.0": {
+        "sha256": "e3fe4ac4b851c468cc8363d500db52c2ead036020723024a109d37346efaa761",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/h11-0.14.0-py3-none-any.whl"
+    },
     "h5py==3.11.0": {
         "sha256": "67462d0669f8f5459529de179f7771bd697389fcb3faab54d63bf788599a48ea",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/h5py-3.11.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
@@ -155,6 +239,10 @@
         "sha256": "bc5dd2abb727a5319567b7a813e6a2e7318c39f4f487cfe6c89c6f9c7d25197d",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/jinja2-3.1.4-py3-none-any.whl"
     },
+    "jmespath==1.0.1": {
+        "sha256": "02e2e4cc71b5bcab88332eebf907519190dd9e6e82107fa7f83b1003a6252980",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/jmespath-1.0.1-py3-none-any.whl"
+    },
     "keras==3.5.0": {
         "sha256": "d37a3c623935713473ceb25241b52bce9d1e0ff5b36e5d0f6f47ed55f8500c9a",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/keras-3.5.0-py3-none-any.whl"
@@ -167,6 +255,10 @@
         "sha256": "c533091d8a3bbf7460a00cb6c1a71da93bffe148f172c7d03b1c31fbf8aa2a0b",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/libclang-18.1.1-py2.py3-none-manylinux2010_x86_64.whl"
     },
+    "mako==1.3.5": {
+        "sha256": "260f1dbc3a519453a9c856dedfe4beb4e50bd5a26d96386cb6c80856556bb91a",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/Mako-1.3.5-py3-none-any.whl"
+    },
     "markdown==3.7": {
         "sha256": "7eb6df5690b81a1d7942992c97fad2938e956e79df20cbc6186e9c3a77b1c803",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/Markdown-3.7-py3-none-any.whl"
@@ -315,6 +407,10 @@
         "sha256": "2d7a1657e36a80ea911db832a8a6ece5ee53d8de21edd5cc5879af6530b1bfee",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/platformdirs-4.2.2-py3-none-any.whl"
     },
+    "plotly==5.24.1": {
+        "sha256": "f67073a1e637eb0dc3e46324d9d51e2fe76e9727c892dde64ddf1e1b51f29089",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/plotly-5.24.1-py3-none-any.whl"
+    },
     "promise==2.3": {
         "sha256": "d10acd69e1aed4de5840e3915edf51c877dfc7c7ae440fd081019edbf62820a4",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/promise-2.3-py3-none-any.whl"
@@ -331,6 +427,18 @@
         "sha256": "5eb499c081ff03ffed8edaa115325edf46eda7f89b53793a4b70dfc72180cc31",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/pycairo-1.26.1-cp39-cp39-manylinux_2_34_x86_64.whl"
     },
+    "pycparser==2.22": {
+        "sha256": "c3702b6d3dd8c7abc1afa565d7e63d53a1d0bd86cdc24edd75470f4de499cfcc",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/pycparser-2.22-py3-none-any.whl"
+    },
+    "pydantic==2.9.2": {
+        "sha256": "f048cec7b26778210e28a0459867920654d48e5e62db0958433636cde4254f12",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/pydantic-2.9.2-py3-none-any.whl"
+    },
+    "pydantic_core==2.23.4": {
+        "sha256": "1278e0d324f6908e872730c9102b0112477a7f7cf88b308e4fc36ce1bdb6d58c",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/pydantic_core-2.23.4-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+    },
     "pygments==2.18.0": {
         "sha256": "b8e6aca0523f3ab76fee51799c488e38782ac06eafcf95e7ba832985c8e7b13a",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/pygments-2.18.0-py3-none-any.whl"
@@ -371,10 +479,18 @@
         "sha256": "70761cfe03c773ceb22aa2f671b4757976145175cdfca038c02654d061d6dcc6",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/requests-2.32.3-py3-none-any.whl"
     },
+    "restrictedpython==7.2": {
+        "sha256": "139cb41da6e57521745a566d05825f7a09e6a884f7fa922568cff0a70b84ce6b",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/RestrictedPython-7.2-py3-none-any.whl"
+    },
     "rich==13.8.0": {
         "sha256": "2e85306a063b9492dffc86278197a60cbece75bcb766022f3436f567cae11bdc",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/rich-13.8.0-py3-none-any.whl"
     },
+    "s3transfer==0.10.2": {
+        "sha256": "eca1c20de70a39daee580aef4986996620f365c4e0fda6a86100231d62f1bf69",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/s3transfer-0.10.2-py3-none-any.whl"
+    },
     "scipy==1.13.1": {
         "sha256": "637e98dcf185ba7f8e663e122ebf908c4702420477ae52a04f9908707456ba4d",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/scipy-1.13.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
@@ -391,6 +507,18 @@
         "sha256": "8abb2f1d86890a2dfb989f9a77cfcfd3e47c2a354b01111771326f8aa26e0254",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/six-1.16.0-py2.py3-none-any.whl"
     },
+    "sniffio==1.3.1": {
+        "sha256": "2f6da418d1f1e0fddd844478f41680e794e6051915791a034ff65e5f100525a2",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/sniffio-1.3.1-py3-none-any.whl"
+    },
+    "sqlalchemy==2.0.35": {
+        "sha256": "890da8cd1941fa3dab28c5bac3b9da8502e7e366f895b3b8e500896f12f94d11",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/SQLAlchemy-2.0.35-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+    },
+    "starlette==0.38.6": {
+        "sha256": "4517a1409e2e73ee4951214ba012052b9e16f60e90d73cfb06192c19203bbb05",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/starlette-0.38.6-py3-none-any.whl"
+    },
     "sympy==1.13.2": {
         "sha256": "c51d75517712f1aed280d4ce58506a4a88d635d6b5dd48b39102a7ae1f3fcfe9",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/sympy-1.13.2-py3-none-any.whl"
@@ -399,6 +527,10 @@
         "sha256": "024ca478df22e9340661486f85298cff5f6dcdba14f3813e8830015b9ed1948f",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tabulate-0.9.0-py3-none-any.whl"
     },
+    "tenacity==9.0.0": {
+        "sha256": "93de0c98785b27fcf659856aa9f54bfbd399e29969b0621bc7f762bd441b4539",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tenacity-9.0.0-py3-none-any.whl"
+    },
     "tensorboard==2.17.1": {
         "sha256": "253701a224000eeca01eee6f7e978aea7b408f60b91eb0babdb04e78947b773e",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tensorboard-2.17.1-py3-none-any.whl"
@@ -423,6 +555,10 @@
         "sha256": "cb84d8e159128aeae7b3f6013ccd7969c69d2e6d1a7b255dbfa6f5344d962986",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tensorflow_metadata-1.15.0-py3-none-any.whl"
     },
+    "tensorflow_probability==0.24.0": {
+        "sha256": "8c1774683e38359dbcaf3697e79b7e6a4e69b9c7b3679e78ee18f43e59e5759b",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tensorflow_probability-0.24.0-py2.py3-none-any.whl"
+    },
     "tensorstore==0.1.64": {
         "sha256": "72f76231ce12bfd266358a096e9c6000a2d86c1f4f24c3891c29b2edfffc5df4",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tensorstore-0.1.64-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
@@ -431,6 +567,10 @@
         "sha256": "9297c0df9c99445c2412e832e882a7884038a25617c60cea2ad69488d4040d63",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/termcolor-2.4.0-py3-none-any.whl"
     },
+    "tf_keras==2.17.0": {
+        "sha256": "cc97717e4dc08487f327b0740a984043a9e0123c7a4e21206711669d3ec41c88",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tf_keras-2.17.0-py3-none-any.whl"
+    },
     "toml==0.10.2": {
         "sha256": "806143ae5bfb6a3c6e736a764057db0e6a0e05e338b5630894a5f779cabb4f9b",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/toml-0.10.2-py2.py3-none-any.whl"
@@ -463,9 +603,13 @@
         "sha256": "9068bc196136463f5245e51efda838afa15aaeca9903f49050dfa2679db4d252",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tzdata-2024.1-py2.py3-none-any.whl"
     },
-    "urllib3==2.2.2": {
-        "sha256": "a448b2f64d686155468037e1ace9f2d2199776e17f0a46610480d311f73e3472",
-        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/urllib3-2.2.2-py3-none-any.whl"
+    "urllib3==1.26.20": {
+        "sha256": "0ed14ccfbf1c30a9072c7ca157e4319b70d65f623e91e7b32fadb2853431016e",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/urllib3-1.26.20-py2.py3-none-any.whl"
+    },
+    "uvicorn==0.30.6": {
+        "sha256": "65fd46fe3fda5bdc1b03b94eb634923ff18cd35b2f084813ea79d1f103f711b5",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/uvicorn-0.30.6-py3-none-any.whl"
     },
     "validators==0.34.0": {
         "sha256": "c804b476e3e6d3786fa07a30073a4ef694e617805eb1946ceee3fe5a9b8b1321",
@@ -475,6 +619,10 @@
         "sha256": "726eef8f8c634ac6584f86c9c53353a010d9f311f6c15a034f3800a7a891d941",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/watchdog-5.0.2-py3-none-manylinux2014_x86_64.whl"
     },
+    "websockets==13.1": {
+        "sha256": "6d2aad13a200e5934f5a6767492fb07151e1de1d6079c003ab31e1823733ae79",
+        "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/websockets-13.1-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+    },
     "werkzeug==3.0.4": {
         "sha256": "02c9eb92b7d6c06f31a782811505d2157837cea66aaede3e217c7c27c039476c",
         "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/werkzeug-3.0.4-py3-none-any.whl"
diff --git a/y2024_bot3/BUILD b/y2024_bot3/BUILD
new file mode 100644
index 0000000..c766a54
--- /dev/null
+++ b/y2024_bot3/BUILD
@@ -0,0 +1,309 @@
+load("//aos:config.bzl", "aos_config")
+load("//aos/util:config_validator_macro.bzl", "config_validator_test")
+load("//frc971:downloader.bzl", "robot_downloader")
+
+config_validator_test(
+    name = "config_validator_test",
+    config = "//y2024_bot3:aos_config",
+)
+
+robot_downloader(
+    binaries = [
+        "//aos/network:web_proxy_main",
+        "//aos/events/logging:log_cat",
+        "//y2024_bot3/constants:constants_sender",
+        "//aos/events:aos_timing_report_streamer",
+    ],
+    data = [
+        ":aos_config",
+        "//aos/starter:roborio_irq_config.json",
+        "//y2024_bot3/constants:constants.json",
+        "@ctre_phoenix6_api_cpp_athena//:shared_libraries",
+        "@ctre_phoenix6_tools_athena//:shared_libraries",
+        "@ctre_phoenix_api_cpp_athena//:shared_libraries",
+        "@ctre_phoenix_cci_athena//:shared_libraries",
+    ],
+    dirs = [
+        "//y2024_bot3/www:www_files",
+    ],
+    start_binaries = [
+        "//aos/events/logging:logger_main",
+        "//aos/network:web_proxy_main",
+        "//aos/starter:irq_affinity",
+        ":joystick_reader",
+        ":wpilib_interface",
+        "//frc971/can_logger",
+        "//aos/network:message_bridge_client",
+        "//aos/network:message_bridge_server",
+        "//y2024_bot3/control_loops/superstructure:superstructure",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+)
+
+robot_downloader(
+    name = "orin_download",
+    binaries = [
+        "//frc971/wpilib:joystick_republish",
+        "//aos/events:aos_timing_report_streamer",
+        "//aos/events/logging:log_cat",
+        "//aos:aos_jitter",
+        "//aos/network:web_proxy_main",
+        "//aos/starter:irq_affinity",
+        "//aos/util:foxglove_websocket",
+        "//frc971/image_streamer:image_streamer",
+        "//frc971/orin:hardware_monitor",
+        "//frc971/orin:argus_monitor",
+        "//frc971/vision:intrinsics_calibration",
+        "//aos/util:filesystem_monitor",
+        "//y2024_bot3/vision:viewer",
+        "//y2024_bot3/constants:constants_sender",
+        "//frc971/orin:localizer_logger",
+        "//frc971/vision:foxglove_image_converter",
+    ],
+    data = [
+        ":aos_config",
+        "//frc971/orin:orin_irq_config.json",
+        "//y2024_bot3/constants:constants.json",
+        "//y2024_bot3/vision:image_streamer_start",
+        "//y2024_bot3/www:www_files",
+    ],
+    dirs = [
+        "//y2024_bot3/www:www_files",
+        "//frc971/image_streamer/www:www_files",
+    ],
+    start_binaries = [
+        "//aos/events/logging:logger_main",
+        "//frc971/imu_fdcan:can_translator",
+        "//frc971/imu_fdcan:dual_imu_blender",
+        "//aos/network:message_bridge_client",
+        "//aos/network:message_bridge_server",
+        "//aos/network:web_proxy_main",
+        "//aos/starter:irq_affinity",
+        "//frc971/orin:argus_camera",
+        "//y2024_bot3/orin:can_logger",
+        "//y2024_bot3/vision:apriltag_detector",
+        "//frc971/vision:image_logger",
+    ],
+    target_compatible_with = ["//tools/platforms/hardware:raspberry_pi"],
+    target_type = "pi",
+)
+
+aos_config(
+    name = "aos_config",
+    src = "y2024_bot3.json",
+    flatbuffers = [
+        "//aos/network:message_bridge_client_fbs",
+        "//aos/network:message_bridge_server_fbs",
+        "//aos/network:timestamp_fbs",
+        "//frc971/input:robot_state_fbs",
+        "//frc971/vision:vision_fbs",
+        "//frc971/vision:target_map_fbs",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+    deps = [
+        ":config_imu",
+        ":config_orin1",
+        ":config_roborio",
+    ],
+)
+
+aos_config(
+    name = "config_imu",
+    src = "y2024_bot3_imu.json",
+    flatbuffers = [
+        "//aos/network:message_bridge_client_fbs",
+        "//aos/network:message_bridge_server_fbs",
+        "//frc971/imu_fdcan:dual_imu_fbs",
+        "//frc971/imu_fdcan:can_translator_status_fbs",
+        "//frc971/imu_fdcan:dual_imu_blender_status_fbs",
+        "//y2024_bot3/constants:constants_fbs",
+        "//frc971/control_loops/drivetrain/localization:localizer_output_fbs",
+        "//frc971/can_logger:can_logging_fbs",
+        "//frc971/orin:hardware_stats_fbs",
+        "//aos/network:timestamp_fbs",
+        "//aos/util:filesystem_fbs",
+        "//aos/network:remote_message_fbs",
+        "//frc971/vision:calibration_fbs",
+        "//frc971/vision:target_map_fbs",
+        "//frc971/vision:vision_fbs",
+        "@com_github_foxglove_schemas//:schemas",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+    deps = [
+        "//aos/events:aos_config",
+        "//frc971/control_loops/drivetrain:aos_config",
+    ],
+)
+
+aos_config(
+    name = "config_roborio",
+    src = "y2024_bot3_roborio.json",
+    flatbuffers = [
+        "//frc971:can_configuration_fbs",
+        "//aos/network:remote_message_fbs",
+        "//aos/network:message_bridge_client_fbs",
+        "//aos/network:message_bridge_server_fbs",
+        "//frc971/wpilib:pdp_values_fbs",
+        "//y2024_bot3/constants:constants_fbs",
+        "//aos/network:timestamp_fbs",
+        "//y2024_bot3/control_loops/superstructure:superstructure_goal_fbs",
+        "//frc971/control_loops/drivetrain:drivetrain_can_position_fbs",
+        "//y2024_bot3/control_loops/superstructure:superstructure_can_position_fbs",
+        "//y2024_bot3/control_loops/superstructure:superstructure_output_fbs",
+        "//frc971/control_loops/drivetrain:rio_localizer_inputs_fbs",
+        "//y2024_bot3/control_loops/superstructure:superstructure_position_fbs",
+        "//frc971/control_loops/drivetrain/localization:localizer_output_fbs",
+        "//y2024_bot3/control_loops/superstructure:superstructure_status_fbs",
+        "//frc971/can_logger:can_logging_fbs",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    deps = [
+        "//aos/events:aos_config",
+        "//frc971/control_loops/drivetrain:aos_config",
+        "//frc971/input:aos_config",
+    ],
+)
+
+aos_config(
+    name = "config_orin1",
+    src = "y2024_bot3_orin1.json",
+    flatbuffers = [
+        "//aos/network:message_bridge_client_fbs",
+        "//aos/network:message_bridge_server_fbs",
+        "//aos/network:timestamp_fbs",
+        "//aos/network:remote_message_fbs",
+        "//y2024_bot3/constants:constants_fbs",
+        "//frc971/control_loops/drivetrain/localization:localizer_output_fbs",
+        "//frc971/orin:hardware_stats_fbs",
+        "//frc971/vision:calibration_fbs",
+        "//frc971/vision:target_map_fbs",
+        "//frc971/vision:vision_fbs",
+        "//aos/util:filesystem_fbs",
+        "@com_github_foxglove_schemas//:schemas",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+    deps = [
+        "//aos/events:aos_config",
+        "//frc971/control_loops/drivetrain:aos_config",
+        "//frc971/input:aos_config",
+    ],
+)
+
+cc_library(
+    name = "constants",
+    srcs = [
+        "constants.cc",
+    ],
+    hdrs = [
+        "constants.h",
+    ],
+    visibility = ["//visibility:public"],
+    deps = [
+        "//aos/mutex",
+        "//aos/network:team_number",
+        "//frc971:constants",
+        "//frc971/control_loops:pose",
+        "//frc971/control_loops:static_zeroing_single_dof_profiled_subsystem",
+        "//frc971/zeroing:absolute_encoder",
+        "//frc971/zeroing:pot_and_absolute_encoder",
+        "//y2024_bot3/constants:constants_fbs",
+        "@com_google_absl//absl/base",
+        "@com_google_absl//absl/log",
+        "@com_google_absl//absl/log:check",
+    ],
+)
+
+cc_binary(
+    name = "wpilib_interface",
+    srcs = [
+        "wpilib_interface.cc",
+    ],
+    target_compatible_with = ["//tools/platforms/hardware:roborio"],
+    deps = [
+        ":constants",
+        "//aos:init",
+        "//aos:math",
+        "//aos/containers:sized_array",
+        "//aos/events:shm_event_loop",
+        "//aos/logging",
+        "//aos/stl_mutex",
+        "//aos/time",
+        "//aos/util:log_interval",
+        "//aos/util:phased_loop",
+        "//aos/util:wrapping_counter",
+        "//frc971:can_configuration_fbs",
+        "//frc971/constants:constants_sender_lib",
+        "//frc971/control_loops:control_loop",
+        "//frc971/control_loops:control_loops_fbs",
+        "//frc971/control_loops/drivetrain:drivetrain_can_position_fbs",
+        "//frc971/control_loops/drivetrain:drivetrain_position_fbs",
+        "//frc971/input:robot_state_fbs",
+        "//frc971/queues:gyro_fbs",
+        "//frc971/wpilib:ADIS16448",
+        "//frc971/wpilib:buffered_pcm",
+        "//frc971/wpilib:can_drivetrain_writer",
+        "//frc971/wpilib:can_sensor_reader",
+        "//frc971/wpilib:dma",
+        "//frc971/wpilib:drivetrain_writer",
+        "//frc971/wpilib:encoder_and_potentiometer",
+        "//frc971/wpilib:generic_can_writer",
+        "//frc971/wpilib:joystick_sender",
+        "//frc971/wpilib:logging_fbs",
+        "//frc971/wpilib:pdp_fetcher",
+        "//frc971/wpilib:sensor_reader",
+        "//frc971/wpilib:talonfx",
+        "//frc971/wpilib:wpilib_robot_base",
+        "//third_party:phoenix",
+        "//third_party:phoenix6",
+        "//third_party:wpilib",
+        "//y2024_bot3/constants:constants_fbs",
+        "//y2024_bot3/control_loops/superstructure:superstructure_can_position_fbs",
+        "//y2024_bot3/control_loops/superstructure:superstructure_output_fbs",
+        "//y2024_bot3/control_loops/superstructure:superstructure_position_fbs",
+    ],
+)
+
+cc_binary(
+    name = "joystick_reader",
+    srcs = [
+        ":joystick_reader.cc",
+    ],
+    deps = [
+        ":constants",
+        "//aos:init",
+        "//aos/actions:action_lib",
+        "//aos/logging",
+        "//frc971/constants:constants_sender_lib",
+        "//frc971/control_loops:profiled_subsystem_fbs",
+        "//frc971/control_loops:static_zeroing_single_dof_profiled_subsystem",
+        "//frc971/input:action_joystick_input",
+        "//frc971/input:drivetrain_input",
+        "//frc971/input:joystick_input",
+        "//frc971/input:redundant_joystick_data",
+        "//y2024_bot3/control_loops/superstructure:superstructure_goal_fbs",
+        "//y2024_bot3/control_loops/superstructure:superstructure_status_fbs",
+    ],
+)
+
+py_library(
+    name = "python_init",
+    srcs = ["__init__.py"],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+)
+
+sh_binary(
+    name = "log_web_proxy",
+    srcs = ["log_web_proxy.sh"],
+    data = [
+        ":aos_config",
+        "//aos/network:log_web_proxy_main",
+        "//frc971/www:starter_main_bundle.min.js",
+        "//y2024_bot3/www:field_main_bundle.min.js",
+        "//y2024_bot3/www:files",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+)
diff --git a/y2024_bot3/__init__.py b/y2024_bot3/__init__.py
new file mode 100644
index 0000000..e69de29
--- /dev/null
+++ b/y2024_bot3/__init__.py
diff --git a/y2024_bot3/constants.cc b/y2024_bot3/constants.cc
new file mode 100644
index 0000000..9b97566
--- /dev/null
+++ b/y2024_bot3/constants.cc
@@ -0,0 +1,41 @@
+#include "y2024_bot3/constants.h"
+
+#include <cinttypes>
+#include <map>
+
+#if __has_feature(address_sanitizer)
+#include "sanitizer/lsan_interface.h"
+#endif
+
+#include "absl/base/call_once.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
+
+#include "aos/mutex/mutex.h"
+#include "aos/network/team_number.h"
+
+namespace y2024_bot3::constants {
+
+Values MakeValues(uint16_t team) {
+  LOG(INFO) << "creating a Constants for team: " << team;
+
+  Values r;
+
+  switch (team) {
+    // A set of constants for tests.
+    case 1:
+      break;
+
+    case kThirdRobotTeamNumber:
+      break;
+
+    default:
+      LOG(FATAL) << "unknown team: " << team;
+  }
+
+  return r;
+}
+
+Values MakeValues() { return MakeValues(aos::network::GetTeamNumber()); }
+
+}  // namespace y2024_bot3::constants
diff --git a/y2024_bot3/constants.h b/y2024_bot3/constants.h
new file mode 100644
index 0000000..31d104f
--- /dev/null
+++ b/y2024_bot3/constants.h
@@ -0,0 +1,53 @@
+#ifndef Y2024_BOT3_CONSTANTS_H_
+#define Y2024_BOT3_CONSTANTS_H_
+
+#include <array>
+#include <cmath>
+#include <cstdint>
+
+#include "frc971/constants.h"
+#include "frc971/control_loops/pose.h"
+#include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h"
+#include "frc971/zeroing/absolute_encoder.h"
+#include "frc971/zeroing/pot_and_absolute_encoder.h"
+#include "y2024_bot3/constants/constants_generated.h"
+
+namespace y2024_bot3::constants {
+
+constexpr uint16_t kThirdRobotTeamNumber = 9971;
+
+struct Values {
+  static const int kSuperstructureCANWriterPriority = 35;
+
+  struct PotAndAbsEncoderConstants {
+    ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemParams<
+        ::frc971::zeroing::PotAndAbsoluteEncoderZeroingEstimator>
+        subsystem_params;
+    double potentiometer_offset;
+  };
+
+  struct AbsoluteEncoderConstants {
+    ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemParams<
+        ::frc971::zeroing::AbsoluteEncoderZeroingEstimator>
+        subsystem_params;
+  };
+
+  struct PotConstants {
+    ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemParams<
+        ::frc971::zeroing::RelativeEncoderZeroingEstimator>
+        subsystem_params;
+    double potentiometer_offset;
+  };
+};
+
+// Creates and returns a Values instance for the constants.
+// Should be called before realtime because this allocates memory.
+// Only the first call to either of these will be used.
+constants::Values MakeValues(uint16_t team);
+
+// Calls MakeValues with aos::network::GetTeamNumber()
+constants::Values MakeValues();
+
+}  // namespace y2024_bot3::constants
+
+#endif  // Y2024_BOT3_CONSTANTS_H_
diff --git a/y2024_bot3/constants/9971.json b/y2024_bot3/constants/9971.json
new file mode 100644
index 0000000..5583b44
--- /dev/null
+++ b/y2024_bot3/constants/9971.json
@@ -0,0 +1,18 @@
+{
+  "cameras": [
+    {
+      "calibration": {% include 'y2024_bot3/constants/calib_files/calibration_imu-9971-0_cam-24-10_2024-02-24_16-44-05.json' %}
+    },
+    {
+      "calibration": {% include 'y2024_bot3/constants/calib_files/calibration_imu-9971-1_cam-24-12_2024-03-24_11-52-49.json' %}
+    },
+    {
+      "calibration": {% include 'y2024_bot3/constants/calib_files/calibration_orin1-9971-0_cam-24-09_2024-03-24_11-52-49.json' %}
+    },
+    {
+      "calibration": {% include 'y2024_bot3/constants/calib_files/calibration_orin1-9971-1_cam-24-11_2024-03-24_11-52-49.json' %}
+    }
+  ],
+  "robot": {},
+  {% include 'y2024_bot3/constants/common.json' %}
+}
diff --git a/y2024_bot3/constants/BUILD b/y2024_bot3/constants/BUILD
new file mode 100644
index 0000000..1ce69a0
--- /dev/null
+++ b/y2024_bot3/constants/BUILD
@@ -0,0 +1,106 @@
+load("//aos/flatbuffers:generate.bzl", "static_flatbuffer")
+load("//tools/build_rules:template.bzl", "jinja2_template")
+load("//y2024_bot3/constants:validator.bzl", "constants_json")
+
+cc_library(
+    name = "simulated_constants_sender",
+    srcs = ["simulated_constants_sender.cc"],
+    hdrs = ["simulated_constants_sender.h"],
+    data = [":test_constants.json"],
+    visibility = ["//y2024_bot3:__subpackages__"],
+    deps = [
+        ":constants_fbs",
+        ":constants_list_fbs",
+        "//aos/events:simulated_event_loop",
+        "//aos/testing:path",
+        "//frc971/constants:constants_sender_lib",
+    ],
+)
+
+jinja2_template(
+    name = "test_constants_unvalidated.json",
+    src = "test_constants.jinja2.json",
+    includes = glob([
+        "test_data/*.json",
+    ]) + [
+        "common.jinja2",
+        "common.json",
+        "//y2024_bot3/constants/calib_files",
+        "//y2024_bot3/vision/maps",
+    ],
+    parameters = {},
+    visibility = ["//visibility:public"],
+)
+
+jinja2_template(
+    name = "constants_unvalidated.json",
+    src = "constants.jinja2.json",
+    includes = [
+        "9971.json",
+        "common.jinja2",
+        "common.json",
+        "//y2024_bot3/constants/calib_files",
+        "//y2024_bot3/vision/maps",
+    ],
+    parameters = {},
+    visibility = ["//visibility:public"],
+)
+
+static_flatbuffer(
+    name = "constants_fbs",
+    srcs = ["constants.fbs"],
+    visibility = ["//visibility:public"],
+    deps = [
+        "//frc971/control_loops:profiled_subsystem_fbs",
+        "//frc971/vision:calibration_fbs",
+        "//frc971/vision:target_map_fbs",
+        "//frc971/zeroing:constants_fbs",
+    ],
+)
+
+static_flatbuffer(
+    name = "constants_list_fbs",
+    srcs = ["constants_list.fbs"],
+    visibility = ["//visibility:public"],
+    deps = [":constants_fbs"],
+)
+
+cc_binary(
+    name = "constants_sender",
+    srcs = ["constants_sender.cc"],
+    visibility = ["//visibility:public"],
+    deps = [
+        ":constants_fbs",
+        ":constants_list_fbs",
+        "//aos:init",
+        "//aos/events:shm_event_loop",
+        "//aos/testing:path",
+        "//frc971/constants:constants_sender_lib",
+    ],
+)
+
+cc_binary(
+    name = "constants_formatter",
+    srcs = ["constants_formatter.cc"],
+    data = [":constants_unvalidated.json"],
+    visibility = ["//visibility:public"],
+    deps = [
+        ":constants_list_fbs",
+        "//aos:init",
+        "//aos:json_to_flatbuffer",
+        "@com_google_absl//absl/log",
+        "@com_google_absl//absl/log:check",
+    ],
+)
+
+constants_json(
+    name = "constants_json",
+    src = ":constants_unvalidated.json",
+    out = "constants.json",
+)
+
+constants_json(
+    name = "test_constants_json",
+    src = ":test_constants_unvalidated.json",
+    out = "test_constants.json",
+)
diff --git a/y2024_bot3/constants/calib_files/BUILD b/y2024_bot3/constants/calib_files/BUILD
new file mode 100644
index 0000000..1f33d50
--- /dev/null
+++ b/y2024_bot3/constants/calib_files/BUILD
@@ -0,0 +1,5 @@
+filegroup(
+    name = "calib_files",
+    srcs = glob(["*.json"]),
+    visibility = ["//visibility:public"],
+)
diff --git a/y2024_bot3/constants/calib_files/calibration_imu-9971-0_cam-24-10_2024-02-24_16-44-05.json b/y2024_bot3/constants/calib_files/calibration_imu-9971-0_cam-24-10_2024-02-24_16-44-05.json
new file mode 100755
index 0000000..e5f50e3
--- /dev/null
+++ b/y2024_bot3/constants/calib_files/calibration_imu-9971-0_cam-24-10_2024-02-24_16-44-05.json
@@ -0,0 +1,46 @@
+{
+ "node_name": "imu",
+ "team_number": 9971,
+ "intrinsics": [
+  646.04834,
+  0.0,
+  703.327576,
+  0.0,
+  645.444458,
+  527.86261,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "fixed_extrinsics": {
+  "data": [
+   0.0,
+   -0.258819,
+   -0.965926,
+   -0.323293,
+   1.0,
+   0.0,
+   -0.0,
+   0.268249,
+   0.0,
+   -0.965926,
+   0.258819,
+   0.471129,
+   0.0,
+   0.0,
+   0.0,
+   1.0
+  ]
+ },
+ "dist_coeffs": [
+  -0.251594,
+  0.064935,
+  0.000479,
+  0.000036,
+  -0.007207
+ ],
+ "calibration_timestamp": 1708821845975708672,
+ "camera_id": "24-10",
+ "camera_number": 0,
+ "reprojection_error": 1.523209
+}
diff --git a/y2024_bot3/constants/calib_files/calibration_imu-9971-1_cam-24-12_2024-03-24_11-52-49.json b/y2024_bot3/constants/calib_files/calibration_imu-9971-1_cam-24-12_2024-03-24_11-52-49.json
new file mode 100755
index 0000000..530e88a
--- /dev/null
+++ b/y2024_bot3/constants/calib_files/calibration_imu-9971-1_cam-24-12_2024-03-24_11-52-49.json
@@ -0,0 +1,46 @@
+{
+ "node_name": "imu",
+ "team_number": 9971,
+ "intrinsics": [
+  647.19928,
+  0.0,
+  690.698181,
+  0.0,
+  646.449158,
+  530.162842,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "fixed_extrinsics": {
+  "data": [
+   0.99969,
+   0.020217,
+   -0.014527,
+   0.160342,
+   0.009501,
+   0.229548,
+   0.973251,
+   0.25208,
+   0.023011,
+   -0.973088,
+   0.229284,
+   0.41504,
+   0.0,
+   0.0,
+   0.0,
+   1.0
+  ]
+ },
+ "dist_coeffs": [
+  -0.249799,
+  0.062593,
+  0.00003,
+  0.000366,
+  -0.006532
+ ],
+ "calibration_timestamp": 1711306369592332476,
+ "camera_id": "24-12",
+ "camera_number": 1,
+ "reprojection_error": 1.23409
+}
\ No newline at end of file
diff --git a/y2024_bot3/constants/calib_files/calibration_orin1-9971-0_cam-24-09_2024-03-24_11-52-49.json b/y2024_bot3/constants/calib_files/calibration_orin1-9971-0_cam-24-09_2024-03-24_11-52-49.json
new file mode 100755
index 0000000..97234c9
--- /dev/null
+++ b/y2024_bot3/constants/calib_files/calibration_orin1-9971-0_cam-24-09_2024-03-24_11-52-49.json
@@ -0,0 +1,46 @@
+{
+ "node_name": "orin1",
+ "team_number": 9971,
+ "intrinsics": [
+  648.187805,
+  0.0,
+  736.903137,
+  0.0,
+  648.028687,
+  557.169861,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "fixed_extrinsics": {
+  "data": [
+   -0.999204,
+   -0.034711,
+   -0.019682,
+   0.162103,
+   0.028118,
+   -0.262536,
+   -0.964512,
+   -0.329348,
+   0.028312,
+   -0.964298,
+   0.263303,
+   0.562319,
+   0.0,
+   0.0,
+   0.0,
+   1.0
+  ]
+ },
+ "dist_coeffs": [
+  -0.265564,
+  0.078084,
+  -0.000231,
+  0.000386,
+  -0.010425
+ ],
+ "calibration_timestamp": 1711306369593360533,
+ "camera_id": "24-09",
+ "camera_number": 0,
+ "reprojection_error": 1.881098
+}
\ No newline at end of file
diff --git a/y2024_bot3/constants/calib_files/calibration_orin1-9971-1_cam-24-11_2024-03-24_11-52-49.json b/y2024_bot3/constants/calib_files/calibration_orin1-9971-1_cam-24-11_2024-03-24_11-52-49.json
new file mode 100755
index 0000000..daef89c
--- /dev/null
+++ b/y2024_bot3/constants/calib_files/calibration_orin1-9971-1_cam-24-11_2024-03-24_11-52-49.json
@@ -0,0 +1,46 @@
+{
+ "node_name": "orin1",
+ "team_number": 9971,
+ "intrinsics": [
+  649.866699,
+  0.0,
+  709.355713,
+  0.0,
+  648.893066,
+  576.101868,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "fixed_extrinsics": {
+  "data": [
+   -0.014623,
+   0.004459,
+   0.999883,
+   0.345385,
+   0.997965,
+   0.062137,
+   0.014318,
+   0.150131,
+   -0.062066,
+   0.998058,
+   -0.005359,
+   0.570236,
+   0.0,
+   0.0,
+   0.0,
+   1.0
+  ]
+ },
+ "dist_coeffs": [
+  -0.248092,
+  0.060938,
+  0.000313,
+  0.00009,
+  -0.006163
+ ],
+ "calibration_timestamp": 1711306369592886702,
+ "camera_id": "24-11",
+ "camera_number": 1,
+ "reprojection_error": 1.450069
+}
\ No newline at end of file
diff --git a/y2024_bot3/constants/common.jinja2 b/y2024_bot3/constants/common.jinja2
new file mode 100644
index 0000000..9b7af82
--- /dev/null
+++ b/y2024_bot3/constants/common.jinja2
@@ -0,0 +1,3 @@
+{% set pi = 3.14159265 %}
+
+{%set zeroing_sample_size = 200 %}
diff --git a/y2024_bot3/constants/common.json b/y2024_bot3/constants/common.json
new file mode 100644
index 0000000..e7b70b4
--- /dev/null
+++ b/y2024_bot3/constants/common.json
@@ -0,0 +1,2 @@
+"common": {
+}
diff --git a/y2024_bot3/constants/constants.fbs b/y2024_bot3/constants/constants.fbs
new file mode 100644
index 0000000..0c7a792
--- /dev/null
+++ b/y2024_bot3/constants/constants.fbs
@@ -0,0 +1,27 @@
+include "frc971/vision/calibration.fbs";
+include "frc971/vision/target_map.fbs";
+include "frc971/control_loops/profiled_subsystem.fbs";
+include "frc971/zeroing/constants.fbs";
+include "frc971/math/matrix.fbs";
+
+namespace y2024_bot3;
+
+table CameraConfiguration {
+  calibration:frc971.vision.calibration.CameraCalibration (id: 0);
+}
+
+table RobotConstants {
+}
+
+// Common table for constants unrelated to the robot
+table Common {
+  target_map:frc971.vision.TargetMap (id: 0);
+}
+
+table Constants {
+  cameras:[CameraConfiguration] (id: 0);
+  robot:RobotConstants (id: 1);
+  common:Common (id: 2);
+}
+
+root_type Constants;
diff --git a/y2024_bot3/constants/constants.jinja2.json b/y2024_bot3/constants/constants.jinja2.json
new file mode 100644
index 0000000..63fad42
--- /dev/null
+++ b/y2024_bot3/constants/constants.jinja2.json
@@ -0,0 +1,8 @@
+{
+  "constants": [
+    {
+      "team": 9971,
+      "data": {% include 'y2024_bot3/constants/9971.json' %}
+    }
+  ]
+}
diff --git a/y2024_bot3/constants/constants_formatter.cc b/y2024_bot3/constants/constants_formatter.cc
new file mode 100644
index 0000000..4b2a601
--- /dev/null
+++ b/y2024_bot3/constants/constants_formatter.cc
@@ -0,0 +1,27 @@
+#include "absl/log/check.h"
+#include "absl/log/log.h"
+
+#include "aos/flatbuffers.h"
+#include "aos/init.h"
+#include "aos/json_to_flatbuffer.h"
+#include "aos/util/file.h"
+#include "y2024_bot3/constants/constants_list_generated.h"
+
+int main(int argc, char **argv) {
+  ::aos::InitGoogle(&argc, &argv);
+
+  CHECK(argc == 3) << ": Expected input and output json files to be passed in.";
+
+  aos::FlatbufferDetachedBuffer<y2024_bot3::ConstantsList> constants =
+      aos::JsonFileToFlatbuffer<y2024_bot3::ConstantsList>(argv[1]);
+
+  // Make sure the file is valid json before we output a formatted version.
+  CHECK(constants.message().constants() != nullptr)
+      << ": Failed to parse " << std::string(argv[2]);
+
+  aos::util::WriteStringToFileOrDie(
+      std::string(argv[2]),
+      aos::FlatbufferToJson(constants, {.multi_line = true}));
+
+  return 0;
+}
diff --git a/y2024_bot3/constants/constants_list.fbs b/y2024_bot3/constants/constants_list.fbs
new file mode 100644
index 0000000..af2b49c
--- /dev/null
+++ b/y2024_bot3/constants/constants_list.fbs
@@ -0,0 +1,14 @@
+include "y2024_bot3/constants/constants.fbs";
+
+namespace y2024_bot3;
+
+table TeamAndConstants {
+  team:long (id: 0);
+  data:Constants (id: 1);
+}
+
+table ConstantsList {
+  constants:[TeamAndConstants] (id: 0);
+}
+
+root_type ConstantsList;
diff --git a/y2024_bot3/constants/constants_sender.cc b/y2024_bot3/constants/constants_sender.cc
new file mode 100644
index 0000000..d74f0d0
--- /dev/null
+++ b/y2024_bot3/constants/constants_sender.cc
@@ -0,0 +1,25 @@
+#include "absl/flags/flag.h"
+
+#include "aos/configuration.h"
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "aos/json_to_flatbuffer.h"
+#include "frc971/constants/constants_sender_lib.h"
+#include "y2024_bot3/constants/constants_generated.h"
+#include "y2024_bot3/constants/constants_list_generated.h"
+
+ABSL_FLAG(std::string, config, "aos_config.json", "Path to the AOS config.");
+ABSL_FLAG(std::string, constants_path, "constants.json",
+          "Path to the constant file");
+
+int main(int argc, char **argv) {
+  aos::InitGoogle(&argc, &argv);
+  aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+      aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
+  aos::ShmEventLoop event_loop(&config.message());
+  frc971::constants::ConstantSender<y2024_bot3::Constants,
+                                    y2024_bot3::ConstantsList>
+      constants_sender(&event_loop, absl::GetFlag(FLAGS_constants_path));
+  // Don't need to call Run().
+  return 0;
+}
diff --git a/y2024_bot3/constants/simulated_constants_sender.cc b/y2024_bot3/constants/simulated_constants_sender.cc
new file mode 100644
index 0000000..77d818a
--- /dev/null
+++ b/y2024_bot3/constants/simulated_constants_sender.cc
@@ -0,0 +1,23 @@
+#include "aos/events/simulated_event_loop.h"
+#include "aos/testing/path.h"
+#include "frc971/constants/constants_sender_lib.h"
+#include "y2024_bot3/constants/constants_generated.h"
+#include "y2024_bot3/constants/constants_list_generated.h"
+
+namespace y2024_bot3 {
+bool SendSimulationConstants(aos::SimulatedEventLoopFactory *factory, int team,
+                             std::string constants_path,
+                             const std::set<std::string_view> &node_names) {
+  for (const aos::Node *node : factory->nodes()) {
+    if (!node_names.empty() &&
+        !node_names.contains(node->name()->string_view())) {
+      continue;
+    }
+    std::unique_ptr<aos::EventLoop> event_loop =
+        factory->MakeEventLoop("constants_sender", node);
+    frc971::constants::ConstantSender<Constants, ConstantsList> sender(
+        event_loop.get(), constants_path, team, "/constants");
+  }
+  return true;
+}
+}  // namespace y2024_bot3
diff --git a/y2024_bot3/constants/simulated_constants_sender.h b/y2024_bot3/constants/simulated_constants_sender.h
new file mode 100644
index 0000000..90b3724
--- /dev/null
+++ b/y2024_bot3/constants/simulated_constants_sender.h
@@ -0,0 +1,21 @@
+#ifndef Y2024_BOT3_CONSTANTS_SIMULATED_CONFIG_SENDER_H_
+#define Y2024_BOT3_CONSTANTS_SIMULATED_CONFIG_SENDER_H_
+
+#include <set>
+
+#include "aos/events/simulated_event_loop.h"
+#include "aos/testing/path.h"
+
+namespace y2024_bot3 {
+// Returns true, to allow this to be easily called in the initializer list of a
+// constructor.
+// If node_names is specified, we limit ourselves to sending constants on the
+// specified nodes.
+bool SendSimulationConstants(
+    aos::SimulatedEventLoopFactory *factory, int team,
+    std::string constants_path =
+        aos::testing::ArtifactPath("y2024_bot3/constants/test_constants.json"),
+    const std::set<std::string_view> &node_names = {});
+}  // namespace y2024_bot3
+
+#endif  // Y2024_BOT3_CONSTANTS_SIMULATED_CONFIG_SENDER_H_
diff --git a/y2024_bot3/constants/test_constants.jinja2.json b/y2024_bot3/constants/test_constants.jinja2.json
new file mode 100644
index 0000000..fdb764a
--- /dev/null
+++ b/y2024_bot3/constants/test_constants.jinja2.json
@@ -0,0 +1,8 @@
+{
+  "constants": [
+    {
+      "team": 9971,
+      "data": {% include 'y2024_bot3/constants/test_data/test_team.json' %}
+    }
+  ]
+}
diff --git a/y2024_bot3/constants/test_data/test_team.json b/y2024_bot3/constants/test_data/test_team.json
new file mode 100644
index 0000000..deacef4
--- /dev/null
+++ b/y2024_bot3/constants/test_data/test_team.json
@@ -0,0 +1,4 @@
+{
+  "robot": {},
+  {% include 'y2024_bot3/constants/common.json' %}
+}
diff --git a/y2024_bot3/constants/validator.bzl b/y2024_bot3/constants/validator.bzl
new file mode 100644
index 0000000..7224e13
--- /dev/null
+++ b/y2024_bot3/constants/validator.bzl
@@ -0,0 +1,13 @@
+load("@aspect_bazel_lib//lib:run_binary.bzl", "run_binary")
+
+# Validates the constants.json file and outputs a formatted version.
+# TODO(max): Make this generic/template it out into frc971
+def constants_json(name, src, out):
+    run_binary(
+        name = name,
+        tool = "//y2024_bot3/constants:constants_formatter",
+        srcs = [src],
+        outs = [out],
+        args = ["$(location %s)" % (src)] + ["$(location %s)" % (out)],
+        visibility = ["//visibility:public"],
+    )
diff --git a/y2024_bot3/control_loops/BUILD b/y2024_bot3/control_loops/BUILD
new file mode 100644
index 0000000..55c0974
--- /dev/null
+++ b/y2024_bot3/control_loops/BUILD
@@ -0,0 +1,6 @@
+py_library(
+    name = "python_init",
+    srcs = ["__init__.py"],
+    visibility = ["//visibility:public"],
+    deps = ["//y2024_bot3:python_init"],
+)
diff --git a/y2024_bot3/control_loops/__init__.py b/y2024_bot3/control_loops/__init__.py
new file mode 100644
index 0000000..e69de29
--- /dev/null
+++ b/y2024_bot3/control_loops/__init__.py
diff --git a/y2024_bot3/control_loops/python/BUILD b/y2024_bot3/control_loops/python/BUILD
new file mode 100644
index 0000000..9ec6b57
--- /dev/null
+++ b/y2024_bot3/control_loops/python/BUILD
@@ -0,0 +1,8 @@
+package(default_visibility = ["//y2024_bot3:__subpackages__"])
+
+py_library(
+    name = "python_init",
+    srcs = ["__init__.py"],
+    visibility = ["//visibility:public"],
+    deps = ["//y2024_bot3/control_loops:python_init"],
+)
diff --git a/y2024_bot3/control_loops/python/__init__.py b/y2024_bot3/control_loops/python/__init__.py
new file mode 100644
index 0000000..e69de29
--- /dev/null
+++ b/y2024_bot3/control_loops/python/__init__.py
diff --git a/y2024_bot3/control_loops/superstructure/BUILD b/y2024_bot3/control_loops/superstructure/BUILD
new file mode 100644
index 0000000..8d909bf
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/BUILD
@@ -0,0 +1,170 @@
+load("@com_github_google_flatbuffers//:typescript.bzl", "flatbuffer_ts_library")
+load("//aos/flatbuffers:generate.bzl", "static_flatbuffer")
+load("//tools/build_rules:js.bzl", "ts_project")
+
+package(default_visibility = ["//visibility:public"])
+
+static_flatbuffer(
+    name = "superstructure_goal_fbs",
+    srcs = [
+        "superstructure_goal.fbs",
+    ],
+    deps = [
+        "//frc971/control_loops:control_loops_fbs",
+        "//frc971/control_loops:profiled_subsystem_fbs",
+    ],
+)
+
+static_flatbuffer(
+    name = "superstructure_output_fbs",
+    srcs = [
+        "superstructure_output.fbs",
+    ],
+)
+
+static_flatbuffer(
+    name = "superstructure_status_fbs",
+    srcs = [
+        "superstructure_status.fbs",
+    ],
+    deps = [
+        "//frc971/control_loops:control_loops_fbs",
+        "//frc971/control_loops:profiled_subsystem_fbs",
+    ],
+)
+
+flatbuffer_ts_library(
+    name = "superstructure_status_ts_fbs",
+    srcs = [
+        "superstructure_status.fbs",
+    ],
+    deps = [
+        "//frc971/control_loops:control_loops_ts_fbs",
+        "//frc971/control_loops:profiled_subsystem_ts_fbs",
+    ],
+)
+
+static_flatbuffer(
+    name = "superstructure_position_fbs",
+    srcs = [
+        "superstructure_position.fbs",
+    ],
+    deps = [
+        "//frc971/control_loops:control_loops_fbs",
+        "//frc971/control_loops:profiled_subsystem_fbs",
+    ],
+)
+
+flatbuffer_ts_library(
+    name = "superstructure_position_ts_fbs",
+    srcs = [
+        "superstructure_position.fbs",
+    ],
+    deps = [
+        "//frc971/control_loops:control_loops_ts_fbs",
+        "//frc971/control_loops:profiled_subsystem_ts_fbs",
+    ],
+)
+
+static_flatbuffer(
+    name = "superstructure_can_position_fbs",
+    srcs = ["superstructure_can_position.fbs"],
+    deps = ["//frc971/control_loops:can_talonfx_fbs"],
+)
+
+flatbuffer_ts_library(
+    name = "superstructure_can_position_ts_fbs",
+    srcs = ["superstructure_can_position.fbs"],
+    target_compatible_with = ["@platforms//os:linux"],
+    deps = ["//frc971/control_loops:can_talonfx_ts_fbs"],
+)
+
+cc_library(
+    name = "superstructure_lib",
+    srcs = [
+        "superstructure.cc",
+    ],
+    hdrs = [
+        "superstructure.h",
+    ],
+    data = [],
+    deps = [
+        ":superstructure_goal_fbs",
+        ":superstructure_output_fbs",
+        ":superstructure_position_fbs",
+        ":superstructure_status_fbs",
+        "//aos:flatbuffer_merge",
+        "//aos/events:event_loop",
+        "//frc971/constants:constants_sender_lib",
+        "//frc971/control_loops:control_loop",
+        "//frc971/zeroing:absolute_encoder",
+        "//frc971/zeroing:pot_and_absolute_encoder",
+        "//y2024_bot3:constants",
+        "//y2024_bot3/constants:constants_fbs",
+        "//y2024_bot3/constants:simulated_constants_sender",
+    ],
+)
+
+cc_binary(
+    name = "superstructure",
+    srcs = [
+        "superstructure_main.cc",
+    ],
+    deps = [
+        ":superstructure_lib",
+        "//aos:init",
+        "//aos/events:shm_event_loop",
+    ],
+)
+
+cc_test(
+    name = "superstructure_lib_test",
+    srcs = [
+        "superstructure_lib_test.cc",
+    ],
+    data = [
+        "//y2024_bot3:aos_config",
+    ],
+    deps = [
+        ":superstructure_can_position_fbs",
+        ":superstructure_goal_fbs",
+        ":superstructure_lib",
+        ":superstructure_output_fbs",
+        ":superstructure_position_fbs",
+        ":superstructure_status_fbs",
+        "//aos:json_to_flatbuffer",
+        "//aos:math",
+        "//aos/events/logging:log_writer",
+        "//aos/testing:googletest",
+        "//aos/time",
+        "//frc971/control_loops:capped_test_plant",
+        "//frc971/control_loops:control_loop_test",
+        "//frc971/control_loops:position_sensor_sim",
+        "//frc971/control_loops:subsystem_simulator",
+        "//frc971/control_loops:team_number_test_environment",
+    ],
+)
+
+cc_binary(
+    name = "superstructure_replay",
+    srcs = ["superstructure_replay.cc"],
+    deps = [
+        ":superstructure_lib",
+        "//aos:configuration",
+        "//aos:init",
+        "//aos/events:simulated_event_loop",
+        "//aos/events/logging:log_reader",
+        "//aos/network:team_number",
+    ],
+)
+
+ts_project(
+    name = "superstructure_plotter",
+    srcs = ["superstructure_plotter.ts"],
+    target_compatible_with = ["@platforms//os:linux"],
+    deps = [
+        "//aos/network/www:aos_plotter",
+        "//aos/network/www:colors",
+        "//aos/network/www:proxy",
+    ],
+)
diff --git a/y2024_bot3/control_loops/superstructure/superstructure.cc b/y2024_bot3/control_loops/superstructure/superstructure.cc
new file mode 100644
index 0000000..c18da15
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure.cc
@@ -0,0 +1,71 @@
+#include "y2024_bot3/control_loops/superstructure/superstructure.h"
+
+#include <chrono>
+
+#include "aos/events/event_loop.h"
+#include "aos/flatbuffer_merge.h"
+#include "aos/network/team_number.h"
+#include "aos/time/time.h"
+#include "frc971/zeroing/wrap.h"
+
+ABSL_FLAG(bool, ignore_distance, false,
+          "If true, ignore distance when shooting and obey joystick_reader");
+
+namespace y2024_bot3::control_loops::superstructure {
+
+using ::aos::monotonic_clock;
+
+using frc971::control_loops::AbsoluteEncoderProfiledJointStatus;
+using frc971::control_loops::PotAndAbsoluteEncoderProfiledJointStatus;
+using frc971::control_loops::RelativeEncoderProfiledJointStatus;
+
+Superstructure::Superstructure(::aos::EventLoop *event_loop,
+                               const ::std::string &name)
+    : frc971::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
+                                                                    name),
+      constants_fetcher_(event_loop),
+      robot_constants_(&constants_fetcher_.constants()),
+      joystick_state_fetcher_(
+          event_loop->MakeFetcher<aos::JoystickState>("/aos")) {
+  event_loop->SetRuntimeRealtimePriority(30);
+}
+
+bool PositionNear(double position, double goal, double threshold) {
+  return std::abs(position - goal) < threshold;
+}
+
+void Superstructure::RunIteration(const Goal *unsafe_goal,
+                                  const Position *position,
+                                  aos::Sender<Output>::Builder *output,
+                                  aos::Sender<Status>::Builder *status) {
+  (void)position;
+
+  if (WasReset()) {
+    AOS_LOG(ERROR, "WPILib reset, restarting\n");
+  }
+
+  OutputT output_struct;
+
+  if (unsafe_goal != nullptr) {
+  }
+
+  if (joystick_state_fetcher_.Fetch() &&
+      joystick_state_fetcher_->has_alliance()) {
+    alliance_ = joystick_state_fetcher_->alliance();
+  }
+
+  if (output) {
+    output->CheckOk(output->Send(Output::Pack(*output->fbb(), &output_struct)));
+  }
+
+  Status::Builder status_builder = status->MakeBuilder<Status>();
+
+  const bool zeroed = true;
+  const bool estopped = false;
+
+  status_builder.add_zeroed(zeroed);
+  status_builder.add_estopped(estopped);
+
+  (void)status->Send(status_builder.Finish());
+}
+}  // namespace y2024_bot3::control_loops::superstructure
diff --git a/y2024_bot3/control_loops/superstructure/superstructure.h b/y2024_bot3/control_loops/superstructure/superstructure.h
new file mode 100644
index 0000000..6362bc0
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure.h
@@ -0,0 +1,55 @@
+#ifndef Y2024_BOT3_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
+#define Y2024_BOT3_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
+
+#include "aos/events/event_loop.h"
+#include "aos/json_to_flatbuffer.h"
+#include "aos/time/time.h"
+#include "frc971/constants/constants_sender_lib.h"
+#include "frc971/control_loops/control_loop.h"
+#include "frc971/zeroing/absolute_encoder.h"
+#include "frc971/zeroing/pot_and_absolute_encoder.h"
+#include "y2024_bot3/constants.h"
+#include "y2024_bot3/constants/constants_generated.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_goal_generated.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_output_generated.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_position_generated.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_status_generated.h"
+
+namespace y2024_bot3::control_loops::superstructure {
+
+class Superstructure
+    : public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
+ public:
+  using AbsoluteEncoderSubsystem =
+      ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystem<
+          ::frc971::zeroing::AbsoluteEncoderZeroingEstimator,
+          ::frc971::control_loops::AbsoluteEncoderProfiledJointStatus>;
+
+  using PotAndAbsoluteEncoderSubsystem =
+      ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystem<
+          ::frc971::zeroing::PotAndAbsoluteEncoderZeroingEstimator,
+          ::frc971::control_loops::PotAndAbsoluteEncoderProfiledJointStatus>;
+
+  explicit Superstructure(::aos::EventLoop *event_loop,
+                          const ::std::string &name = "/superstructure");
+
+  double robot_velocity() const;
+
+ protected:
+  virtual void RunIteration(const Goal *unsafe_goal, const Position *position,
+                            aos::Sender<Output>::Builder *output,
+                            aos::Sender<Status>::Builder *status) override;
+
+ private:
+  frc971::constants::ConstantsFetcher<Constants> constants_fetcher_;
+  const Constants *robot_constants_;
+  aos::Fetcher<aos::JoystickState> joystick_state_fetcher_;
+
+  aos::Alliance alliance_ = aos::Alliance::kInvalid;
+
+  DISALLOW_COPY_AND_ASSIGN(Superstructure);
+};
+
+}  // namespace y2024_bot3::control_loops::superstructure
+
+#endif  // Y2024_BOT3_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
diff --git a/y2024_bot3/control_loops/superstructure/superstructure_can_position.fbs b/y2024_bot3/control_loops/superstructure/superstructure_can_position.fbs
new file mode 100644
index 0000000..15a0565
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure_can_position.fbs
@@ -0,0 +1,16 @@
+include "frc971/control_loops/can_talonfx.fbs";
+
+namespace y2024_bot3.control_loops.superstructure;
+
+table CANPosition {
+    // The timestamp of the measurement on the canivore clock in nanoseconds
+    // This will have less jitter than the
+    // timestamp of the message being sent out.
+    timestamp:int64 (id: 0, deprecated);
+
+    // The ctre::phoenix::StatusCode of the measurement
+    // Should be OK = 0
+    status:int (id: 1);
+}
+
+root_type CANPosition;
diff --git a/y2024_bot3/control_loops/superstructure/superstructure_goal.fbs b/y2024_bot3/control_loops/superstructure/superstructure_goal.fbs
new file mode 100644
index 0000000..947f740
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure_goal.fbs
@@ -0,0 +1,7 @@
+include "frc971/control_loops/profiled_subsystem.fbs";
+
+namespace y2024_bot3.control_loops.superstructure;
+
+table Goal {
+}
+root_type Goal;
diff --git a/y2024_bot3/control_loops/superstructure/superstructure_lib_test.cc b/y2024_bot3/control_loops/superstructure/superstructure_lib_test.cc
new file mode 100644
index 0000000..fe26af2
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure_lib_test.cc
@@ -0,0 +1,243 @@
+#include <chrono>
+#include <memory>
+
+#include "absl/flags/flag.h"
+#include "gtest/gtest.h"
+
+#include "aos/events/logging/log_writer.h"
+#include "frc971/control_loops/capped_test_plant.h"
+#include "frc971/control_loops/control_loop_test.h"
+#include "frc971/control_loops/position_sensor_sim.h"
+#include "frc971/control_loops/subsystem_simulator.h"
+#include "frc971/control_loops/team_number_test_environment.h"
+#include "frc971/zeroing/absolute_encoder.h"
+#include "y2024_bot3/constants/simulated_constants_sender.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_can_position_generated.h"
+
+ABSL_FLAG(std::string, output_folder, "",
+          "If set, logs all channels to the provided logfile.");
+
+namespace y2024_bot3::control_loops::superstructure::testing {
+
+namespace chrono = std::chrono;
+
+using ::aos::monotonic_clock;
+using ::frc971::CreateProfileParameters;
+using ::frc971::control_loops::CappedTestPlant;
+using ::frc971::control_loops::
+    CreateStaticZeroingSingleDOFProfiledSubsystemGoal;
+using ::frc971::control_loops::PositionSensorSimulator;
+using ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal;
+typedef Superstructure::PotAndAbsoluteEncoderSubsystem
+    PotAndAbsoluteEncoderSubsystem;
+typedef Superstructure::AbsoluteEncoderSubsystem AbsoluteEncoderSubsystem;
+using PotAndAbsoluteEncoderSimulator =
+    frc971::control_loops::SubsystemSimulator<
+        frc971::control_loops::PotAndAbsoluteEncoderProfiledJointStatus,
+        PotAndAbsoluteEncoderSubsystem::State,
+        constants::Values::PotAndAbsEncoderConstants>;
+using AbsoluteEncoderSimulator = frc971::control_loops::SubsystemSimulator<
+    frc971::control_loops::AbsoluteEncoderProfiledJointStatus,
+    AbsoluteEncoderSubsystem::State,
+    constants::Values::AbsoluteEncoderConstants>;
+
+class SuperstructureSimulation {
+ public:
+  SuperstructureSimulation(::aos::EventLoop *event_loop,
+                           const Constants *simulated_robot_constants,
+                           chrono::nanoseconds dt)
+      : event_loop_(event_loop),
+        dt_(dt),
+        superstructure_position_sender_(
+            event_loop_->MakeSender<Position>("/superstructure")),
+        superstructure_can_position_sender_(
+            event_loop_->MakeSender<CANPosition>("/superstructure/rio")),
+        superstructure_status_fetcher_(
+            event_loop_->MakeFetcher<Status>("/superstructure")),
+        superstructure_output_fetcher_(
+            event_loop_->MakeFetcher<Output>("/superstructure")) {
+    (void)dt_;
+    (void)simulated_robot_constants;
+
+    phased_loop_handle_ = event_loop_->AddPhasedLoop(
+        [this](int) {
+          // Skip this the first time.
+          if (!first_) {
+            EXPECT_TRUE(superstructure_output_fetcher_.Fetch());
+            EXPECT_TRUE(superstructure_status_fetcher_.Fetch());
+          }
+          first_ = false;
+          SendPositionMessage();
+        },
+        dt);
+  }
+
+  // Sends a queue message with the position of the superstructure.
+  void SendPositionMessage() {
+    ::aos::Sender<Position>::Builder builder =
+        superstructure_position_sender_.MakeBuilder();
+
+    Position::Builder position_builder = builder.MakeBuilder<Position>();
+
+    CHECK_EQ(builder.Send(position_builder.Finish()),
+             aos::RawSender::Error::kOk);
+  }
+
+ private:
+  ::aos::EventLoop *event_loop_;
+  const chrono::nanoseconds dt_;
+  ::aos::PhasedLoopHandler *phased_loop_handle_ = nullptr;
+
+  ::aos::Sender<Position> superstructure_position_sender_;
+  ::aos::Sender<CANPosition> superstructure_can_position_sender_;
+  ::aos::Fetcher<Status> superstructure_status_fetcher_;
+  ::aos::Fetcher<Output> superstructure_output_fetcher_;
+
+  bool first_ = true;
+};
+
+class SuperstructureTest : public ::frc971::testing::ControlLoopTest {
+ public:
+  SuperstructureTest()
+      : ::frc971::testing::ControlLoopTest(
+            aos::configuration::ReadConfig("y2024_bot3/aos_config.json"),
+            std::chrono::microseconds(5000)),
+        simulated_constants_dummy_(SendSimulationConstants(
+            event_loop_factory(), 9971,
+            "y2024_bot3/constants/test_constants.json")),
+        roborio_(aos::configuration::GetNode(configuration(), "roborio")),
+        logger_pi_(aos::configuration::GetNode(configuration(), "logger")),
+        superstructure_event_loop(MakeEventLoop("Superstructure", roborio_)),
+        superstructure_(superstructure_event_loop.get()),
+        test_event_loop_(MakeEventLoop("test", roborio_)),
+        constants_fetcher_(test_event_loop_.get()),
+        simulated_robot_constants_(&constants_fetcher_.constants()),
+        superstructure_goal_fetcher_(
+            test_event_loop_->MakeFetcher<Goal>("/superstructure")),
+        superstructure_goal_sender_(
+            test_event_loop_->MakeSender<Goal>("/superstructure")),
+        superstructure_status_fetcher_(
+            test_event_loop_->MakeFetcher<Status>("/superstructure")),
+        superstructure_output_fetcher_(
+            test_event_loop_->MakeFetcher<Output>("/superstructure")),
+        superstructure_position_fetcher_(
+            test_event_loop_->MakeFetcher<Position>("/superstructure")),
+        superstructure_position_sender_(
+            test_event_loop_->MakeSender<Position>("/superstructure")),
+        superstructure_can_position_sender_(
+            test_event_loop_->MakeSender<CANPosition>("/superstructure/rio")),
+        superstructure_plant_event_loop_(MakeEventLoop("plant", roborio_)),
+        superstructure_plant_(superstructure_plant_event_loop_.get(),
+                              simulated_robot_constants_, dt()) {
+    set_team_id(frc971::control_loops::testing::kTeamNumber);
+
+    SetEnabled(true);
+
+    if (!absl::GetFlag(FLAGS_output_folder).empty()) {
+      unlink(absl::GetFlag(FLAGS_output_folder).c_str());
+      logger_event_loop_ = MakeEventLoop("logger", roborio_);
+      logger_ = std::make_unique<aos::logger::Logger>(logger_event_loop_.get());
+      logger_->StartLoggingOnRun(absl::GetFlag(FLAGS_output_folder));
+    }
+  }
+
+  void VerifyNearGoal() {
+    superstructure_goal_fetcher_.Fetch();
+    superstructure_status_fetcher_.Fetch();
+    superstructure_output_fetcher_.Fetch();
+
+    ASSERT_FALSE(superstructure_status_fetcher_->estopped());
+
+    ASSERT_TRUE(superstructure_goal_fetcher_.get() != nullptr) << ": No goal";
+    ASSERT_TRUE(superstructure_status_fetcher_.get() != nullptr)
+        << ": No status";
+    ASSERT_TRUE(superstructure_output_fetcher_.get() != nullptr)
+        << ": No output";
+  }
+
+  void CheckIfZeroed() {
+    superstructure_status_fetcher_.Fetch();
+    ASSERT_TRUE(superstructure_status_fetcher_.get()->zeroed());
+  }
+
+  void WaitUntilZeroed() {
+    int i = 0;
+    do {
+      i++;
+      RunFor(dt());
+      superstructure_status_fetcher_.Fetch();
+      // 2 Seconds
+
+      ASSERT_LE(i, 2.0 / ::aos::time::DurationInSeconds(dt()));
+
+      // Since there is a delay when sending running, make sure we have a
+      // status before checking it.
+    } while (superstructure_status_fetcher_.get() == nullptr ||
+             !superstructure_status_fetcher_.get()->zeroed());
+  }
+
+  void WaitUntilNear() {}
+
+  const bool simulated_constants_dummy_;
+
+  const aos::Node *const roborio_;
+  const aos::Node *const logger_pi_;
+
+  ::std::unique_ptr<::aos::EventLoop> superstructure_event_loop;
+  ::y2024_bot3::control_loops::superstructure::Superstructure superstructure_;
+  ::std::unique_ptr<::aos::EventLoop> test_event_loop_;
+  ::aos::PhasedLoopHandler *phased_loop_handle_ = nullptr;
+
+  frc971::constants::ConstantsFetcher<Constants> constants_fetcher_;
+  const Constants *simulated_robot_constants_;
+
+  ::aos::Fetcher<Goal> superstructure_goal_fetcher_;
+  ::aos::Sender<Goal> superstructure_goal_sender_;
+  ::aos::Fetcher<Status> superstructure_status_fetcher_;
+  ::aos::Fetcher<Output> superstructure_output_fetcher_;
+  ::aos::Fetcher<Position> superstructure_position_fetcher_;
+  ::aos::Sender<Position> superstructure_position_sender_;
+  ::aos::Sender<CANPosition> superstructure_can_position_sender_;
+
+  ::std::unique_ptr<::aos::EventLoop> superstructure_plant_event_loop_;
+  SuperstructureSimulation superstructure_plant_;
+
+  std::unique_ptr<aos::EventLoop> logger_event_loop_;
+  std::unique_ptr<aos::logger::Logger> logger_;
+
+  const ::std::vector<::Eigen::Matrix<double, 3, 1>> points_;
+};
+
+// Tests that the superstructure does nothing when the goal is to remain
+// still.
+
+TEST_F(SuperstructureTest, DoesNothing) {
+  SetEnabled(true);
+  WaitUntilZeroed();
+
+  {
+    auto builder = superstructure_goal_sender_.MakeBuilder();
+    Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+
+    ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
+  }
+  RunFor(chrono::seconds(10));
+
+  VerifyNearGoal();
+}
+
+// Tests that the loop zeroes when run for a while without a goal.
+TEST_F(SuperstructureTest, ZeroNoGoal) {
+  SetEnabled(true);
+  WaitUntilZeroed();
+  RunFor(chrono::seconds(2));
+}
+
+// Tests that running disabled works
+TEST_F(SuperstructureTest, DisableTest) {
+  RunFor(chrono::seconds(2));
+  CheckIfZeroed();
+}
+
+}  // namespace y2024_bot3::control_loops::superstructure::testing
diff --git a/y2024_bot3/control_loops/superstructure/superstructure_main.cc b/y2024_bot3/control_loops/superstructure/superstructure_main.cc
new file mode 100644
index 0000000..a7d048c
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure_main.cc
@@ -0,0 +1,25 @@
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure.h"
+
+ABSL_FLAG(std::string, arm_trajectories, "arm_trajectories_generated.bfbs",
+          "The path to the generated arm trajectories bfbs file.");
+
+using y2024_bot3::control_loops::superstructure::Superstructure;
+
+int main(int argc, char **argv) {
+  ::aos::InitGoogle(&argc, &argv);
+
+  aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+      aos::configuration::ReadConfig("aos_config.json");
+
+  ::aos::ShmEventLoop event_loop(&config.message());
+
+  frc971::constants::WaitForConstants<y2024_bot3::Constants>(&config.message());
+
+  Superstructure superstructure(&event_loop);
+
+  event_loop.Run();
+
+  return 0;
+}
diff --git a/y2024_bot3/control_loops/superstructure/superstructure_output.fbs b/y2024_bot3/control_loops/superstructure/superstructure_output.fbs
new file mode 100644
index 0000000..28799de
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure_output.fbs
@@ -0,0 +1,6 @@
+namespace y2024_bot3.control_loops.superstructure;
+
+table Output {
+}
+
+root_type Output;
diff --git a/y2024_bot3/control_loops/superstructure/superstructure_plotter.ts b/y2024_bot3/control_loops/superstructure/superstructure_plotter.ts
new file mode 100644
index 0000000..f3c90aa
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure_plotter.ts
@@ -0,0 +1,117 @@
+// Provides a plot for debugging robot state-related issues.
+import {AosPlotter, MessageHandler} from '../../../aos/network/www/aos_plotter';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from '../../../aos/network/www/colors';
+import * as proxy from '../../../aos/network/www/proxy';
+
+import Connection = proxy.Connection;
+
+const TIME = AosPlotter.TIME;
+const DEFAULT_WIDTH = AosPlotter.DEFAULT_WIDTH * 2;
+const DEFAULT_HEIGHT = AosPlotter.DEFAULT_HEIGHT * 1;
+
+// plot static zeroing single dof subsystem (generic function used by specific subsystem plotters)
+function plotSzsdofSubsystem(
+    name: string, plotter: AosPlotter, element: Element, position: MessageHandler, positionName: string,
+    status: MessageHandler, statusName: string, output: MessageHandler, outputName: string, hasPot:boolean = true): void {
+  {
+    const positionPlot =
+        plotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
+    positionPlot.plot.getAxisLabels().setTitle(name + ' Position');
+    positionPlot.plot.getAxisLabels().setXLabel(TIME);
+    positionPlot.plot.getAxisLabels().setYLabel('Position [rad,m]');
+    positionPlot.addMessageLine(position, [positionName, 'encoder'])
+        .setColor(RED);
+    positionPlot.addMessageLine(position, [positionName, 'absolute_encoder'])
+        .setColor(GREEN);
+    if (hasPot) {
+      positionPlot.addMessageLine(position, [positionName, 'pot'])
+          .setColor(BLUE);
+    }
+    positionPlot
+        .addMessageLine(status, [statusName, 'estimator_state', 'position'])
+        .setColor(BROWN);
+    positionPlot.addMessageLine(status, [statusName, 'position'])
+        .setColor(WHITE);
+  }
+  {
+    const statesPlot =
+        plotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
+    statesPlot.plot.getAxisLabels().setTitle(name + ' State');
+    statesPlot.plot.getAxisLabels().setXLabel(TIME);
+    statesPlot.plot.getAxisLabels().setYLabel('[bool,ZeroingError]');
+    statesPlot.addMessageLine(status, [statusName, 'estopped']).setColor(RED);
+    statesPlot.addMessageLine(status, [statusName, 'zeroed']).setColor(GREEN);
+    statesPlot
+        .addMessageLine(status, [statusName, 'estimator_state', 'errors[]'])
+        .setColor(BLUE)
+        .setDrawLine(false);
+  }
+  {
+    const positionConvergencePlot =
+        plotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
+    positionConvergencePlot.plot.getAxisLabels().setTitle(name + ' Position Goals');
+    positionConvergencePlot.plot.getAxisLabels().setXLabel(TIME);
+    positionConvergencePlot.plot.getAxisLabels().setYLabel('[rad,m]');
+    positionConvergencePlot.addMessageLine(status, [statusName, 'position'])
+        .setColor(RED);
+    positionConvergencePlot.addMessageLine(status, [statusName, 'goal_position'])
+        .setColor(GREEN);
+    positionConvergencePlot
+        .addMessageLine(status, [statusName, 'unprofiled_goal_position'])
+        .setColor(BROWN);
+  }
+  {
+    const velocityConvergencePlot =
+        plotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
+    velocityConvergencePlot.plot.getAxisLabels().setTitle(name + ' Velocity Goals');
+    velocityConvergencePlot.plot.getAxisLabels().setXLabel(TIME);
+    velocityConvergencePlot.plot.getAxisLabels().setYLabel('[rad,m]');
+    velocityConvergencePlot.addMessageLine(status, [statusName, 'velocity'])
+        .setColor(RED);
+    velocityConvergencePlot.addMessageLine(status, [statusName, 'calculated_velocity'])
+        .setColor(RED).setDrawLine(false);
+    velocityConvergencePlot.addMessageLine(status, [statusName, 'goal_velocity'])
+        .setColor(GREEN);
+    velocityConvergencePlot
+        .addMessageLine(status, [statusName, 'unprofiled_goal_velocity'])
+        .setColor(BROWN);
+  }
+  {
+    const outputPlot =
+        plotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
+    outputPlot.plot.getAxisLabels().setTitle(name + ' Outputs');
+    outputPlot.plot.getAxisLabels().setXLabel(TIME);
+    outputPlot.plot.getAxisLabels().setYLabel('[volts]');
+    outputPlot.addMessageLine(output, [outputName])
+        .setColor(RED);
+    outputPlot.addMessageLine(status, [statusName, 'voltage_error'])
+        .setColor(GREEN);
+    outputPlot.addMessageLine(status, [statusName, 'position_power'])
+        .setColor(BLUE);
+    outputPlot.addMessageLine(status, [statusName, 'velocity_power'])
+        .setColor(BROWN);
+    outputPlot.addMessageLine(status, [statusName, 'feedforwards_power'])
+        .setColor(WHITE);
+  }
+}
+
+export function plotSuperstructure(conn: Connection, element: Element): void {
+  const aosPlotter = new AosPlotter(conn);
+  const status = aosPlotter.addMessageSource(
+      '/superstructure', 'y2024_bot3.control_loops.superstructure.Status');
+  const robotState = aosPlotter.addMessageSource('/aos', 'aos.RobotState');
+
+  {
+    const robotStatePlot =
+        aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
+    robotStatePlot.plot.getAxisLabels().setTitle('Robot State Plot');
+    robotStatePlot.plot.getAxisLabels().setXLabel(TIME);
+    robotStatePlot.plot.getAxisLabels().setYLabel('[bool]');
+    robotStatePlot.addMessageLine(robotState, ['outputs_enabled'])
+        .setColor(RED);
+    robotStatePlot.addMessageLine(status, ['zeroed'])
+        .setColor(GREEN);
+    robotStatePlot.addMessageLine(status, ['estopped'])
+        .setColor(BLUE);
+  }
+}
diff --git a/y2024_bot3/control_loops/superstructure/superstructure_position.fbs b/y2024_bot3/control_loops/superstructure/superstructure_position.fbs
new file mode 100644
index 0000000..f0553a5
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure_position.fbs
@@ -0,0 +1,9 @@
+include "frc971/control_loops/control_loops.fbs";
+include "frc971/control_loops/profiled_subsystem.fbs";
+
+namespace y2024_bot3.control_loops.superstructure;
+
+table Position {
+}
+
+root_type Position;
diff --git a/y2024_bot3/control_loops/superstructure/superstructure_replay.cc b/y2024_bot3/control_loops/superstructure/superstructure_replay.cc
new file mode 100644
index 0000000..1058f4f
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure_replay.cc
@@ -0,0 +1,75 @@
+// This binary allows us to replay the superstructure code over existing
+// logfile. When you run this code, it generates a new logfile with the data all
+// replayed, so that it can then be run through the plotting tool or analyzed
+// in some other way. The original superstructure status data will be on the
+// /original/superstructure channel.
+#include "absl/flags/flag.h"
+
+#include "aos/events/logging/log_reader.h"
+#include "aos/events/logging/log_writer.h"
+#include "aos/events/simulated_event_loop.h"
+#include "aos/init.h"
+#include "aos/json_to_flatbuffer.h"
+#include "aos/logging/log_message_generated.h"
+#include "aos/network/team_number.h"
+#include "y2024_bot3/constants.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure.h"
+
+ABSL_FLAG(int32_t, team, 971, "Team number to use for logfile replay.");
+ABSL_FLAG(std::string, output_folder, "/tmp/superstructure_replay/",
+          "Logs all channels to the provided logfile.");
+
+int main(int argc, char **argv) {
+  aos::InitGoogle(&argc, &argv);
+
+  aos::network::OverrideTeamNumber(absl::GetFlag(FLAGS_team));
+
+  // open logfiles
+  aos::logger::LogReader reader(
+      aos::logger::SortParts(aos::logger::FindLogs(argc, argv)));
+  // TODO(james): Actually enforce not sending on the same buses as the logfile
+  // spews out.
+  reader.RemapLoggedChannel("/superstructure",
+                            "y2024_bot3.control_loops.superstructure.Status");
+  reader.RemapLoggedChannel("/superstructure",
+                            "y2024_bot3.control_loops.superstructure.Output");
+
+  aos::SimulatedEventLoopFactory factory(reader.configuration());
+  reader.Register(&factory);
+
+  aos::NodeEventLoopFactory *roborio =
+      factory.GetNodeEventLoopFactory("roborio");
+
+  unlink(absl::GetFlag(FLAGS_output_folder).c_str());
+  std::unique_ptr<aos::EventLoop> logger_event_loop =
+      roborio->MakeEventLoop("logger");
+  auto logger = std::make_unique<aos::logger::Logger>(logger_event_loop.get());
+  logger->StartLoggingOnRun(absl::GetFlag(FLAGS_output_folder));
+
+  roborio->OnStartup([roborio]() {
+    roborio->AlwaysStart<
+        y2024_bot3::control_loops::superstructure::Superstructure>(
+        "superstructure");
+  });
+
+  std::unique_ptr<aos::EventLoop> print_loop = roborio->MakeEventLoop("print");
+  print_loop->SkipAosLog();
+  print_loop->MakeWatcher(
+      "/aos", [&print_loop](const aos::logging::LogMessageFbs &msg) {
+        LOG(INFO) << print_loop->context().monotonic_event_time << " "
+                  << aos::FlatbufferToJson(&msg);
+      });
+  print_loop->MakeWatcher(
+      "/superstructure",
+      [&](const y2024_bot3::control_loops::superstructure::Status &status) {
+        if (status.estopped()) {
+          LOG(ERROR) << "Estopped";
+        }
+      });
+
+  factory.Run();
+
+  reader.Deregister();
+
+  return 0;
+}
diff --git a/y2024_bot3/control_loops/superstructure/superstructure_status.fbs b/y2024_bot3/control_loops/superstructure/superstructure_status.fbs
new file mode 100644
index 0000000..ca5876e
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure_status.fbs
@@ -0,0 +1,14 @@
+include "frc971/control_loops/control_loops.fbs";
+include "frc971/control_loops/profiled_subsystem.fbs";
+
+namespace y2024_bot3.control_loops.superstructure;
+
+table Status {
+  // All subsystems know their location.
+  zeroed:bool (id: 0);
+
+  // If true, we have aborted. This is the or of all subsystem estops.
+  estopped:bool (id: 1);
+}
+
+root_type Status;
diff --git a/y2024_bot3/copy_logs.sh b/y2024_bot3/copy_logs.sh
new file mode 100755
index 0000000..806460f
--- /dev/null
+++ b/y2024_bot3/copy_logs.sh
@@ -0,0 +1,29 @@
+#!/bin/bash
+
+# Helper script to copy most recent logs off of the pis
+
+set -e
+
+ROBOT_PREFIX="99" # ..71  (Should be one of 79, 89, 99, or 9)
+PI_LIST="1 2"     # Should be some set of {1,2,3,4,5,6}
+
+LOG_FILE_PATH=/media/sda1/fbs_log-current
+if [[ -z $1 || ! -d $1 ]]; then
+    echo "Please specify the base directory to store the logs ('$1' not found)"
+    exit -1
+fi
+
+# Create output directory based on given directory + a timestamp
+OUTPUT_DIR=$1"/"`date +"%Y-%m-%dT%H-%M-%S"`
+mkdir ${OUTPUT_DIR}
+
+echo "Copying logs from the robot ${ROBOT_PREFIX}71 and pis ${PI_LIST}"
+echo "Storing logs in folder ${OUTPUT_DIR}"
+
+for pi in $PI_LIST; do
+    echo "========================================================"
+    echo "Copying logs from pi-${ROBOT_PREFIX}71-$pi"
+    echo "========================================================"
+    scp -r pi@10.${ROBOT_PREFIX}.71.10${pi}:${LOG_FILE_PATH} ${OUTPUT_DIR}/fbs_log-pi${pi}
+done
+
diff --git a/y2024_bot3/joystick_reader.cc b/y2024_bot3/joystick_reader.cc
new file mode 100644
index 0000000..4b88402
--- /dev/null
+++ b/y2024_bot3/joystick_reader.cc
@@ -0,0 +1,63 @@
+#include <unistd.h>
+
+#include <cmath>
+#include <cstdio>
+#include <cstring>
+
+#include "absl/flags/flag.h"
+
+#include "aos/actions/actions.h"
+#include "aos/init.h"
+#include "aos/logging/logging.h"
+#include "aos/network/team_number.h"
+#include "aos/util/log_interval.h"
+#include "frc971/autonomous/base_autonomous_actor.h"
+#include "frc971/constants/constants_sender_lib.h"
+#include "frc971/control_loops/drivetrain/localizer_generated.h"
+#include "frc971/control_loops/profiled_subsystem_generated.h"
+#include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h"
+#include "frc971/input/action_joystick_input.h"
+#include "frc971/input/driver_station_data.h"
+#include "frc971/input/drivetrain_input.h"
+#include "frc971/input/joystick_input.h"
+#include "frc971/input/redundant_joystick_data.h"
+#include "frc971/zeroing/wrap.h"
+#include "y2024_bot3/constants/constants_generated.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_goal_static.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_status_static.h"
+
+using frc971::CreateProfileParameters;
+using frc971::input::driver_station::ButtonLocation;
+using frc971::input::driver_station::ControlBit;
+using frc971::input::driver_station::JoystickAxis;
+using frc971::input::driver_station::POVLocation;
+
+namespace y2024_bot3::input::joysticks {
+
+namespace superstructure = y2024_bot3::control_loops::superstructure;
+
+// ButtonLocation constants go here
+
+class Reader : public ::frc971::input::ActionJoystickInput {};
+}  // namespace y2024_bot3::input::joysticks
+
+int main(int argc, char **argv) {
+  ::aos::InitGoogle(&argc, &argv);
+
+  aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+      aos::configuration::ReadConfig("aos_config.json");
+  frc971::constants::WaitForConstants<y2024_bot3::Constants>(&config.message());
+
+  ::aos::ShmEventLoop constant_fetcher_event_loop(&config.message());
+  frc971::constants::ConstantsFetcher<y2024_bot3::Constants> constants_fetcher(
+      &constant_fetcher_event_loop);
+  const y2024_bot3::Constants *robot_constants = &constants_fetcher.constants();
+
+  ::aos::ShmEventLoop event_loop(&config.message());
+  (void)robot_constants;
+  //::y2024_bot3::input::joysticks::Reader reader(&event_loop, robot_constants);
+
+  event_loop.Run();
+
+  return 0;
+}
diff --git a/y2024_bot3/log_web_proxy.sh b/y2024_bot3/log_web_proxy.sh
new file mode 100755
index 0000000..f97bafe
--- /dev/null
+++ b/y2024_bot3/log_web_proxy.sh
@@ -0,0 +1 @@
+./aos/network/log_web_proxy_main --data_dir=y2024_bot3/www $@
diff --git a/y2024_bot3/orin/BUILD b/y2024_bot3/orin/BUILD
new file mode 100644
index 0000000..c8b899b
--- /dev/null
+++ b/y2024_bot3/orin/BUILD
@@ -0,0 +1,16 @@
+cc_binary(
+    name = "can_logger",
+    srcs = [
+        "can_logger_main.cc",
+    ],
+    target_compatible_with = ["@platforms//cpu:arm64"],
+    visibility = ["//visibility:public"],
+    deps = [
+        "//aos:init",
+        "//aos/events:shm_event_loop",
+        "//aos/time",
+        "//frc971/can_logger:can_logger_lib",
+        "@com_google_absl//absl/log",
+        "@com_google_absl//absl/log:check",
+    ],
+)
diff --git a/y2024_bot3/orin/can_logger_main.cc b/y2024_bot3/orin/can_logger_main.cc
new file mode 100644
index 0000000..dcfec69
--- /dev/null
+++ b/y2024_bot3/orin/can_logger_main.cc
@@ -0,0 +1,18 @@
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "frc971/can_logger/can_logger.h"
+
+int main(int argc, char **argv) {
+  ::aos::InitGoogle(&argc, &argv);
+
+  aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+      aos::configuration::ReadConfig("aos_config.json");
+
+  ::aos::ShmEventLoop event_loop(&config.message());
+
+  frc971::can_logger::CanLogger cana_logger(&event_loop, "/can/cana", "cana");
+
+  event_loop.Run();
+
+  return 0;
+}
diff --git a/y2024_bot3/vision/BUILD b/y2024_bot3/vision/BUILD
new file mode 100644
index 0000000..b55d35d
--- /dev/null
+++ b/y2024_bot3/vision/BUILD
@@ -0,0 +1,54 @@
+filegroup(
+    name = "image_streamer_start",
+    srcs = ["image_streamer_start.sh"],
+    visibility = ["//visibility:public"],
+)
+
+cc_binary(
+    name = "apriltag_detector",
+    srcs = [
+        "apriltag_detector.cc",
+        "vision_util.cc",
+        "vision_util.h",
+    ],
+    features = ["cuda"],
+    target_compatible_with = ["@platforms//cpu:arm64"],
+    visibility = ["//visibility:public"],
+    deps = [
+        "//aos:configuration",
+        "//aos:init",
+        "//aos/events:shm_event_loop",
+        "//frc971/orin:gpu_apriltag_lib",
+        "//third_party:cudart",
+        "//third_party/apriltag",
+        "//y2024_bot3/constants:constants_fbs",
+        "@com_github_nvidia_cccl//:cccl",
+        "@com_google_absl//absl/flags:flag",
+        "@com_google_absl//absl/log",
+        "@com_google_absl//absl/log:check",
+    ],
+)
+
+cc_binary(
+    name = "viewer",
+    srcs = [
+        "viewer.cc",
+        "vision_util.cc",
+        "vision_util.h",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = [
+        "//y2024_bot3:__subpackages__",
+    ],
+    deps = [
+        "//aos:init",
+        "//aos:json_to_flatbuffer",
+        "//aos/events:shm_event_loop",
+        "//frc971/constants:constants_sender_lib",
+        "//frc971/vision:vision_fbs",
+        "//frc971/vision:vision_util_lib",
+        "//third_party:opencv",
+        "//y2024_bot3/constants:constants_fbs",
+        "@com_google_absl//absl/strings",
+    ],
+)
diff --git a/y2024_bot3/vision/apriltag_detector.cc b/y2024_bot3/vision/apriltag_detector.cc
new file mode 100644
index 0000000..2c73c58
--- /dev/null
+++ b/y2024_bot3/vision/apriltag_detector.cc
@@ -0,0 +1,54 @@
+
+#include <string>
+
+#include "absl/flags/flag.h"
+
+#include "aos/init.h"
+#include "frc971/orin/gpu_apriltag.h"
+#include "y2024_bot3/constants/constants_generated.h"
+#include "y2024_bot3/vision/vision_util.h"
+
+ABSL_FLAG(std::string, channel, "/camera", "Channel name");
+ABSL_FLAG(std::string, config, "aos_config.json",
+          "Path to the config file to use.");
+
+void GpuApriltagDetector() {
+  aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+      aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
+
+  frc971::constants::WaitForConstants<y2024_bot3::Constants>(&config.message());
+
+  aos::ShmEventLoop event_loop(&config.message());
+
+  const frc971::constants::ConstantsFetcher<y2024_bot3::Constants>
+      calibration_data(&event_loop);
+
+  CHECK(absl::GetFlag(FLAGS_channel).length() == 8);
+  int camera_id = std::stoi(absl::GetFlag(FLAGS_channel).substr(7, 1));
+  const frc971::vision::calibration::CameraCalibration *calibration =
+      y2024_bot3::vision::FindCameraCalibration(
+          calibration_data.constants(),
+          event_loop.node()->name()->string_view(), camera_id);
+
+  frc971::apriltag::ApriltagDetector detector(
+      &event_loop, absl::GetFlag(FLAGS_channel), calibration);
+
+  // TODO(austin): Figure out our core pinning strategy.
+  // event_loop.SetRuntimeAffinity(aos::MakeCpusetFromCpus({5}));
+
+  LOG(INFO) << "Setting scheduler priority";
+  struct sched_param param;
+  param.sched_priority = 21;
+  PCHECK(sched_setscheduler(0, SCHED_FIFO, &param) == 0);
+
+  LOG(INFO) << "Running event loop";
+  // TODO(austin): Pre-warm it...
+  event_loop.Run();
+}  // namespace frc971::apriltag
+
+int main(int argc, char **argv) {
+  aos::InitGoogle(&argc, &argv);
+  GpuApriltagDetector();
+
+  return 0;
+}
diff --git a/y2024_bot3/vision/image_streamer_start.sh b/y2024_bot3/vision/image_streamer_start.sh
new file mode 100755
index 0000000..48d9da7
--- /dev/null
+++ b/y2024_bot3/vision/image_streamer_start.sh
@@ -0,0 +1,22 @@
+#!/bin/bash
+
+# Some configurations to avoid dropping frames
+# 640x480@30fps, 400x300@60fps.
+# Bitrate 500000-1500000
+WIDTH=640
+HEIGHT=480
+BITRATE=1500000
+LISTEN_ON="/camera/downsized"
+# Don't interfere with field webpage
+STREAMING_PORT=1181
+
+# Handle weirdness with openssl and gstreamer
+export OPENSSL_CONF=""
+
+# Enable for verbose logging
+#export GST_DEBUG=4
+
+export LD_LIBRARY_PATH=/usr/lib/aarch64-linux-gnu/gstreamer-1.0
+
+exec ./image_streamer --width=$WIDTH --height=$HEIGHT --bitrate=$BITRATE --listen_on=$LISTEN_ON --config=aos_config.json --streaming_port=$STREAMING_PORT
+
diff --git a/y2024_bot3/vision/maps/BUILD b/y2024_bot3/vision/maps/BUILD
new file mode 100644
index 0000000..38191a4
--- /dev/null
+++ b/y2024_bot3/vision/maps/BUILD
@@ -0,0 +1,7 @@
+filegroup(
+    name = "maps",
+    srcs = glob([
+        "*.json",
+    ]),
+    visibility = ["//visibility:public"],
+)
diff --git a/y2024_bot3/vision/maps/target_map.json b/y2024_bot3/vision/maps/target_map.json
new file mode 100644
index 0000000..2a8dfef
--- /dev/null
+++ b/y2024_bot3/vision/maps/target_map.json
@@ -0,0 +1,236 @@
+{
+/* Targets have positive Z axis pointing into the board, positive X to the right
+   when looking at the board, and positive Y is down when looking at the board.
+   This means that you will get an identity rotation from the camera to target
+   frame when the target is upright, flat, and centered in the camera's view.
+
+   The global frame as the origin at the center of the field, positive X points
+   at the red driver's station, and positive Z points straight up.
+   */
+    "target_poses": [
+        {
+            "id": 1,
+            "position": {
+                "x": 6.809,
+                "y": -3.860,
+                "z": 1.361
+            },
+            "orientation": {
+                "w": 0.1830127,
+                "x": -0.1830127,
+                "y": 0.6830127,
+                "z": -0.6830127
+            }
+        },
+        {
+            "id": 2,
+            "position": {
+                "x": 7.915,
+                "y": -3.223,
+                "z": 1.361
+            },
+            "orientation": {
+                "w": 0.1830127,
+                "x": -0.1830127,
+                "y": 0.6830127,
+                "z": -0.6830127
+            }
+        },
+        {
+            "id": 3,
+            "position": {
+                "x": 8.309,
+                "y": 0.877,
+                "z": 1.456
+            },
+            "orientation": {
+                "w": 0.5,
+                "x": -0.5,
+                "y": 0.5,
+                "z": -0.5
+            }
+        },
+        {
+            "id": 4,
+            "position": {
+                "x": 8.309,
+                "y": 1.442,
+                "z": 1.456
+            },
+            "orientation": {
+                "w": 0.5,
+                "x": -0.5,
+                "y": 0.5,
+                "z": -0.5
+            }
+        },
+        {
+            "id": 5,
+            "position": {
+                "x": 6.428,
+                "y": 4.099,
+                "z": 1.361
+            },
+            "orientation": {
+                "w": 0.7071068,
+                "x": -0.7071068,
+                "y": 0.0,
+                "z": 0.0
+            }
+        },
+        {
+            "id": 6,
+            "position": {
+                "x": -6.430,
+                "y": 4.099,
+                "z": 1.361
+            },
+            "orientation": {
+                "w": 0.7071068,
+                "x": -0.7071068,
+                "y": 0.0,
+                "z": 0.0
+            }
+        },
+        {
+            "id": 7,
+            "position": {
+                "x": -8.309,
+                "y": 1.442,
+                "z": 1.474
+            },
+            "orientation": {
+                "w": 0.5,
+                "x": -0.5,
+                "y": -0.5,
+                "z": 0.5
+            }
+        },
+        {
+            "id": 8,
+            "position": {
+                "x": -8.309,
+                "y": 0.877,
+                "z": 1.474
+            },
+            "orientation": {
+                "w": 0.5,
+                "x": -0.5,
+                "y": -0.5,
+                "z": 0.5
+            }
+        },
+        {
+            "id": 9,
+            "position": {
+                "x": -7.915,
+                "y": -3.223,
+                "z": 1.361
+            },
+            "orientation": {
+                "w": 0.1830127,
+                "x": -0.1830127,
+                "y": -0.6830127,
+                "z": 0.6830127
+            }
+        },
+        {
+            "id": 10,
+            "position": {
+                "x": -6.809,
+                "y": -3.860,
+                "z": 1.361
+            },
+            "orientation": {
+                "w": 0.1830127,
+                "x": -0.1830127,
+                "y": -0.6830127,
+                "z": 0.6830127
+            }
+        },
+        {
+            "id": 11,
+            "position": {
+                "x": 3.629,
+                "y": -0.393,
+                "z": 1.326
+            },
+            "orientation": {
+                "w": 0.6830127,
+                "x": -0.6830127,
+                "y": -0.1830127,
+                "z": 0.1830127
+            }
+        },
+        {
+            "id": 12,
+            "position": {
+                "x": 3.630,
+                "y": 0.392,
+                "z": 1.326
+            },
+            "orientation": {
+                "w": 0.1830127,
+                "x": -0.1830127,
+                "y": -0.6830127,
+                "z": 0.6830127
+            }
+        },
+        {
+            "id": 13,
+            "position": {
+                "x": 2.949,
+                "y": -0.000,
+                "z": 1.326
+            },
+            "orientation": {
+                "w": 0.5,
+                "x": -0.5,
+                "y": 0.5,
+                "z": -0.5
+            }
+        },
+        {
+            "id": 14,
+            "position": {
+                "x": -2.949,
+                "y": -0.000,
+                "z": 1.326
+            },
+            "orientation": {
+                "w": 0.5,
+                "x": -0.5,
+                "y": -0.5,
+                "z": 0.5
+            }
+        },
+        {
+            "id": 15,
+            "position": {
+                "x": -3.629,
+                "y": 0.393,
+                "z": 1.326
+            },
+            "orientation": {
+                "w": 0.1830127,
+                "x": -0.1830127,
+                "y": 0.6830127,
+                "z": -0.6830127
+            }
+        },
+        {
+            "id": 16,
+            "position": {
+                "x": -3.630,
+                "y": -0.392,
+                "z": 1.326
+            },
+            "orientation": {
+                "w": 0.6830127,
+                "x": -0.6830127,
+                "y": 0.1830127,
+                "z": -0.1830127
+            }
+        }
+    ]
+}
diff --git a/y2024_bot3/vision/viewer.cc b/y2024_bot3/vision/viewer.cc
new file mode 100644
index 0000000..2d99fd5
--- /dev/null
+++ b/y2024_bot3/vision/viewer.cc
@@ -0,0 +1,122 @@
+#include "absl/strings/match.h"
+#include <opencv2/calib3d.hpp>
+#include <opencv2/highgui/highgui.hpp>
+#include <opencv2/imgproc.hpp>
+
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "aos/json_to_flatbuffer.h"
+#include "aos/time/time.h"
+#include "frc971/constants/constants_sender_lib.h"
+#include "frc971/vision/vision_generated.h"
+#include "frc971/vision/vision_util_lib.h"
+#include "y2024_bot3/vision/vision_util.h"
+
+ABSL_FLAG(std::string, capture, "",
+          "If set, capture a single image and save it to this filename.");
+ABSL_FLAG(std::string, channel, "/camera", "Channel name for the image.");
+ABSL_FLAG(std::string, config, "aos_config.json",
+          "Path to the config file to use.");
+ABSL_FLAG(int32_t, rate, 100, "Time in milliseconds to wait between images");
+ABSL_FLAG(double, scale, 1.0, "Scale factor for images being displayed");
+
+namespace y2024_bot3::vision {
+namespace {
+
+using frc971::vision::CameraImage;
+
+bool DisplayLoop(const cv::Mat intrinsics, const cv::Mat dist_coeffs,
+                 aos::Fetcher<CameraImage> *image_fetcher) {
+  const CameraImage *image;
+
+  // Read next image
+  if (!image_fetcher->Fetch()) {
+    VLOG(2) << "Couldn't fetch next image";
+    return true;
+  }
+  image = image_fetcher->get();
+  CHECK(image != nullptr) << "Couldn't read image";
+
+  // Create color image:
+  cv::Mat image_color_mat(cv::Size(image->cols(), image->rows()), CV_8UC2,
+                          (void *)image->data()->data());
+  cv::Mat bgr_image(cv::Size(image->cols(), image->rows()), CV_8UC3);
+  cv::cvtColor(image_color_mat, bgr_image, cv::COLOR_YUV2BGR_YUYV);
+
+  if (!absl::GetFlag(FLAGS_capture).empty()) {
+    if (absl::EndsWith(absl::GetFlag(FLAGS_capture), ".bfbs")) {
+      aos::WriteFlatbufferToFile(absl::GetFlag(FLAGS_capture),
+                                 image_fetcher->CopyFlatBuffer());
+    } else {
+      cv::imwrite(absl::GetFlag(FLAGS_capture), bgr_image);
+    }
+
+    return false;
+  }
+
+  cv::Mat undistorted_image;
+  cv::undistort(bgr_image, undistorted_image, intrinsics, dist_coeffs);
+  if (absl::GetFlag(FLAGS_scale) != 1.0) {
+    cv::resize(undistorted_image, undistorted_image, cv::Size(),
+               absl::GetFlag(FLAGS_scale), absl::GetFlag(FLAGS_scale));
+  }
+  cv::imshow("Display", undistorted_image);
+
+  int keystroke = cv::waitKey(1);
+  if ((keystroke & 0xFF) == static_cast<int>('c')) {
+    // Convert again, to get clean image
+    cv::cvtColor(image_color_mat, bgr_image, cv::COLOR_YUV2BGR_YUYV);
+    std::stringstream name;
+    name << "capture-" << aos::realtime_clock::now() << ".png";
+    cv::imwrite(name.str(), bgr_image);
+    LOG(INFO) << "Saved image file: " << name.str();
+  } else if ((keystroke & 0xFF) == static_cast<int>('q')) {
+    return false;
+  }
+  return true;
+}
+
+void ViewerMain() {
+  aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+      aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
+
+  frc971::constants::WaitForConstants<y2024_bot3::Constants>(&config.message());
+
+  aos::ShmEventLoop event_loop(&config.message());
+
+  frc971::constants::ConstantsFetcher<y2024_bot3::Constants> constants_fetcher(
+      &event_loop);
+  CHECK(absl::GetFlag(FLAGS_channel).length() == 8);
+  int camera_id = std::stoi(absl::GetFlag(FLAGS_channel).substr(7, 1));
+  const auto *calibration_data = FindCameraCalibration(
+      constants_fetcher.constants(), event_loop.node()->name()->string_view(),
+      camera_id);
+  const cv::Mat intrinsics = frc971::vision::CameraIntrinsics(calibration_data);
+  const cv::Mat dist_coeffs =
+      frc971::vision::CameraDistCoeffs(calibration_data);
+
+  aos::Fetcher<CameraImage> image_fetcher =
+      event_loop.MakeFetcher<CameraImage>(absl::GetFlag(FLAGS_channel));
+
+  // Run the display loop
+  event_loop.AddPhasedLoop(
+      [&](int) {
+        if (!DisplayLoop(intrinsics, dist_coeffs, &image_fetcher)) {
+          LOG(INFO) << "Calling event_loop Exit";
+          event_loop.Exit();
+        };
+      },
+      ::std::chrono::milliseconds(absl::GetFlag(FLAGS_rate)));
+
+  event_loop.Run();
+
+  image_fetcher = aos::Fetcher<CameraImage>();
+}
+
+}  // namespace
+}  // namespace y2024_bot3::vision
+
+int main(int argc, char **argv) {
+  aos::InitGoogle(&argc, &argv);
+  y2024_bot3::vision::ViewerMain();
+}
diff --git a/y2024_bot3/vision/vision_util.cc b/y2024_bot3/vision/vision_util.cc
new file mode 100644
index 0000000..0f99849
--- /dev/null
+++ b/y2024_bot3/vision/vision_util.cc
@@ -0,0 +1,49 @@
+#include "y2024_bot3/vision/vision_util.h"
+
+#include "absl/log/check.h"
+#include "absl/log/log.h"
+
+namespace y2024_bot3::vision {
+
+// Store a list of ordered cameras as you progress around the robot/box of orins
+std::vector<CameraNode> CreateNodeList() {
+  std::vector<CameraNode> list;
+
+  list.push_back({.node_name = "imu", .camera_number = 0});
+  list.push_back({.node_name = "imu", .camera_number = 1});
+  list.push_back({.node_name = "orin1", .camera_number = 1});
+  list.push_back({.node_name = "orin1", .camera_number = 0});
+
+  return list;
+}
+
+// From the node_list, create a numbering scheme from 0 to 3
+std::map<std::string, int> CreateOrderingMap(
+    std::vector<CameraNode> &node_list) {
+  std::map<std::string, int> map;
+
+  for (uint i = 0; i < node_list.size(); i++) {
+    map.insert({node_list.at(i).camera_name(), i});
+  }
+
+  return map;
+}
+
+const frc971::vision::calibration::CameraCalibration *FindCameraCalibration(
+    const y2024_bot3::Constants &calibration_data, std::string_view node_name,
+    int camera_number) {
+  CHECK(calibration_data.has_cameras());
+  for (const y2024_bot3::CameraConfiguration *candidate :
+       *calibration_data.cameras()) {
+    CHECK(candidate->has_calibration());
+    if (candidate->calibration()->node_name()->string_view() != node_name ||
+        candidate->calibration()->camera_number() != camera_number) {
+      continue;
+    }
+    return candidate->calibration();
+  }
+  LOG(FATAL) << ": Failed to find camera calibration for " << node_name
+             << " and camera number " << camera_number;
+}
+
+}  // namespace y2024_bot3::vision
diff --git a/y2024_bot3/vision/vision_util.h b/y2024_bot3/vision/vision_util.h
new file mode 100644
index 0000000..fc0f29c
--- /dev/null
+++ b/y2024_bot3/vision/vision_util.h
@@ -0,0 +1,41 @@
+#ifndef Y2024_BOT3_VISION_VISION_UTIL_H_
+#define Y2024_BOT3_VISION_VISION_UTIL_H_
+#include <map>
+#include <string_view>
+
+#include "opencv2/imgproc.hpp"
+
+#include "y2024_bot3/constants/constants_generated.h"
+
+namespace y2024_bot3::vision {
+
+// Generate unique colors for each camera
+const auto kOrinColors = std::map<std::string, cv::Scalar>{
+    {"/orin1/camera0", cv::Scalar(255, 0, 255)},
+    {"/orin1/camera1", cv::Scalar(255, 255, 0)},
+    {"/imu/camera0", cv::Scalar(0, 255, 255)},
+    {"/imu/camera1", cv::Scalar(255, 165, 0)},
+};
+
+// Structure to store node name (e.g., orin1, imu), number, and a usable string
+struct CameraNode {
+  std::string node_name;
+  int camera_number;
+
+  inline const std::string camera_name() const {
+    return "/" + node_name + "/camera" + std::to_string(camera_number);
+  }
+};
+
+std::vector<CameraNode> CreateNodeList();
+
+std::map<std::string, int> CreateOrderingMap(
+    std::vector<CameraNode> &node_list);
+
+const frc971::vision::calibration::CameraCalibration *FindCameraCalibration(
+    const y2024_bot3::Constants &calibration_data, std::string_view node_name,
+    int camera_number);
+
+}  // namespace y2024_bot3::vision
+
+#endif  // Y2024_BOT3_VISION_VISION_UTIL_H_
diff --git a/y2024_bot3/wpilib_interface.cc b/y2024_bot3/wpilib_interface.cc
new file mode 100644
index 0000000..b6066e3
--- /dev/null
+++ b/y2024_bot3/wpilib_interface.cc
@@ -0,0 +1,249 @@
+#include <unistd.h>
+
+#include <array>
+#include <chrono>
+#include <cinttypes>
+#include <cstdio>
+#include <cstring>
+#include <functional>
+#include <memory>
+#include <mutex>
+#include <thread>
+
+#include "absl/flags/flag.h"
+
+#include "frc971/wpilib/ahal/AnalogInput.h"
+#include "frc971/wpilib/ahal/DriverStation.h"
+#include "frc971/wpilib/ahal/Encoder.h"
+#include "frc971/wpilib/ahal/TalonFX.h"
+#include "frc971/wpilib/ahal/VictorSP.h"
+#undef ERROR
+
+#include "ctre/phoenix/cci/Diagnostics_CCI.h"
+
+#include "aos/commonmath.h"
+#include "aos/containers/sized_array.h"
+#include "aos/events/event_loop.h"
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "aos/logging/logging.h"
+#include "aos/realtime.h"
+#include "aos/time/time.h"
+#include "aos/util/log_interval.h"
+#include "aos/util/phased_loop.h"
+#include "aos/util/wrapping_counter.h"
+#include "frc971/can_configuration_generated.h"
+#include "frc971/constants/constants_sender_lib.h"
+#include "frc971/input/robot_state_generated.h"
+#include "frc971/queues/gyro_generated.h"
+#include "frc971/wpilib/buffered_pcm.h"
+#include "frc971/wpilib/buffered_solenoid.h"
+#include "frc971/wpilib/can_sensor_reader.h"
+#include "frc971/wpilib/dma.h"
+#include "frc971/wpilib/encoder_and_potentiometer.h"
+#include "frc971/wpilib/generic_can_writer.h"
+#include "frc971/wpilib/joystick_sender.h"
+#include "frc971/wpilib/logging_generated.h"
+#include "frc971/wpilib/loop_output_handler.h"
+#include "frc971/wpilib/pdp_fetcher.h"
+#include "frc971/wpilib/sensor_reader.h"
+#include "frc971/wpilib/talonfx.h"
+#include "frc971/wpilib/wpilib_robot_base.h"
+#include "y2024_bot3/constants.h"
+#include "y2024_bot3/constants/constants_generated.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_can_position_static.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_output_generated.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_position_generated.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_position_static.h"
+
+ABSL_FLAG(bool, ctre_diag_server, false,
+          "If true, enable the diagnostics server for interacting with "
+          "devices on the CAN bus using Phoenix Tuner");
+
+using ::aos::monotonic_clock;
+using ::frc971::CANConfiguration;
+using ::frc971::wpilib::TalonFX;
+using ::y2024_bot3::constants::Values;
+namespace superstructure = ::y2024_bot3::control_loops::superstructure;
+namespace chrono = ::std::chrono;
+using std::make_unique;
+
+namespace y2024_bot3::wpilib {
+namespace {
+
+constexpr double kMaxBringupPower = 12.0;
+
+constexpr double kMaxFastEncoderPulsesPerSecond = std::max({
+    1000000  // arbitrary number because we deleted all the stuff in this array
+});
+
+static_assert(kMaxFastEncoderPulsesPerSecond <= 1300000,
+              "fast encoders are too fast");
+
+}  // namespace
+
+// Class to send position messages with sensor readings to our loops.
+class SensorReader : public ::frc971::wpilib::SensorReader {
+ public:
+  SensorReader(::aos::ShmEventLoop *event_loop,
+               const Constants *robot_constants)
+      : ::frc971::wpilib::SensorReader(event_loop),
+        robot_constants_(robot_constants),
+        superstructure_position_sender_(
+            event_loop->MakeSender<superstructure::PositionStatic>(
+                "/superstructure")) {
+    UpdateFastEncoderFilterHz(kMaxFastEncoderPulsesPerSecond);
+    event_loop->SetRuntimeAffinity(aos::MakeCpusetFromCpus({0}));
+  };
+  void Start() override { AddToDMA(&imu_yaw_rate_reader_); }
+
+  void set_yaw_rate_input(::std::unique_ptr<frc::DigitalInput> sensor) {
+    imu_yaw_rate_input_ = ::std::move(sensor);
+    imu_yaw_rate_reader_.set_input(imu_yaw_rate_input_.get());
+  }
+
+  void RunIteration() override {
+    aos::Sender<superstructure::PositionStatic>::StaticBuilder builder =
+        superstructure_position_sender_.MakeStaticBuilder();
+
+    builder.CheckOk(builder.Send());
+
+    {
+      auto builder = gyro_sender_.MakeBuilder();
+      ::frc971::sensors::GyroReading::Builder gyro_reading_builder =
+          builder.MakeBuilder<::frc971::sensors::GyroReading>();
+
+      builder.CheckOk(builder.Send(gyro_reading_builder.Finish()));
+    }
+  }
+
+ private:
+  const Constants *robot_constants_;
+
+  aos::Sender<superstructure::PositionStatic> superstructure_position_sender_;
+  ::aos::Sender<::frc971::sensors::GyroReading> gyro_sender_;
+
+  std::unique_ptr<frc::DigitalInput> imu_yaw_rate_input_;
+
+  frc971::wpilib::DMAPulseWidthReader imu_yaw_rate_reader_;
+};
+
+class WPILibRobot : public ::frc971::wpilib::WPILibRobotBase {
+ public:
+  ::std::unique_ptr<frc::Encoder> make_encoder(int index) {
+    return make_unique<frc::Encoder>(10 + index * 2, 11 + index * 2, false,
+                                     frc::Encoder::k4X);
+  }
+
+  void Run() override {
+    aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+        aos::configuration::ReadConfig("aos_config.json");
+
+    frc971::constants::WaitForConstants<y2024_bot3::Constants>(
+        &config.message());
+
+    ::aos::ShmEventLoop constant_fetcher_event_loop(&config.message());
+    frc971::constants::ConstantsFetcher<Constants> constants_fetcher(
+        &constant_fetcher_event_loop);
+    const Constants *robot_constants = &constants_fetcher.constants();
+
+    AddLoop(&constant_fetcher_event_loop);
+
+    // Thread 1.
+    ::aos::ShmEventLoop joystick_sender_event_loop(&config.message());
+    ::frc971::wpilib::JoystickSender joystick_sender(
+        &joystick_sender_event_loop);
+    AddLoop(&joystick_sender_event_loop);
+
+    // Thread 2.
+    ::aos::ShmEventLoop pdp_fetcher_event_loop(&config.message());
+    ::frc971::wpilib::PDPFetcher pdp_fetcher(&pdp_fetcher_event_loop);
+    AddLoop(&pdp_fetcher_event_loop);
+
+    // Thread 3.
+    ::aos::ShmEventLoop sensor_reader_event_loop(&config.message());
+    SensorReader sensor_reader(&sensor_reader_event_loop, robot_constants);
+    sensor_reader.set_pwm_trigger(false);
+    sensor_reader.set_yaw_rate_input(make_unique<frc::DigitalInput>(25));
+
+    AddLoop(&sensor_reader_event_loop);
+
+    // Thread 4.
+    // Set up CAN.
+    if (!absl::GetFlag(FLAGS_ctre_diag_server)) {
+      c_Phoenix_Diagnostics_SetSecondsToStart(-1);
+      c_Phoenix_Diagnostics_Dispose();
+    }
+
+    std::vector<ctre::phoenix6::BaseStatusSignal *> canivore_signal_registry;
+    std::vector<ctre::phoenix6::BaseStatusSignal *> rio_signal_registry;
+
+    ::aos::ShmEventLoop can_sensor_reader_event_loop(&config.message());
+    can_sensor_reader_event_loop.set_name("CANSensorReader");
+
+    ::aos::ShmEventLoop rio_sensor_reader_event_loop(&config.message());
+    rio_sensor_reader_event_loop.set_name("RioSensorReader");
+
+    // Creating list of talonfx for CANSensorReader
+    std::vector<std::shared_ptr<TalonFX>> canivore_talonfxs;
+    std::vector<std::shared_ptr<TalonFX>> rio_talonfxs;
+
+    aos::Sender<y2024_bot3::control_loops::superstructure::CANPositionStatic>
+        superstructure_can_position_sender =
+            can_sensor_reader_event_loop.MakeSender<
+                y2024_bot3::control_loops::superstructure::CANPositionStatic>(
+                "/superstructure/canivore");
+
+    aos::Sender<y2024_bot3::control_loops::superstructure::CANPositionStatic>
+        superstructure_rio_position_sender =
+            rio_sensor_reader_event_loop.MakeSender<
+                y2024_bot3::control_loops::superstructure::CANPositionStatic>(
+                "/superstructure/rio");
+
+    frc971::wpilib::CANSensorReader rio_can_sensor_reader(
+        &rio_sensor_reader_event_loop, std::move(rio_signal_registry),
+        rio_talonfxs,
+        [&superstructure_rio_position_sender](
+            ctre::phoenix::StatusCode status) {
+          aos::Sender<
+              y2024_bot3::control_loops::superstructure::CANPositionStatic>::
+              StaticBuilder superstructure_can_builder =
+                  superstructure_rio_position_sender.MakeStaticBuilder();
+
+          superstructure_can_builder->set_status(static_cast<int>(status));
+          superstructure_can_builder.CheckOk(superstructure_can_builder.Send());
+        },
+        frc971::wpilib::CANSensorReader::SignalSync::kNoSync);
+
+    AddLoop(&can_sensor_reader_event_loop);
+    AddLoop(&rio_sensor_reader_event_loop);
+
+    // Thread 5.
+    ::aos::ShmEventLoop can_output_event_loop(&config.message());
+    can_output_event_loop.set_name("CANOutputWriter");
+
+    frc971::wpilib::GenericCANWriter<control_loops::superstructure::Output>
+        can_superstructure_writer(
+            &can_output_event_loop,
+            [](const control_loops::superstructure::Output &output,
+               const std::map<std::string_view, std::shared_ptr<TalonFX>>
+                   &talonfx_map) {
+              (void)output;
+              (void)talonfx_map;
+            });
+
+    can_output_event_loop.MakeWatcher(
+        "/roborio", [&can_superstructure_writer](
+                        const frc971::CANConfiguration &configuration) {
+          can_superstructure_writer.HandleCANConfiguration(configuration);
+        });
+
+    AddLoop(&can_output_event_loop);
+
+    RunLoops();
+  }
+};
+
+}  // namespace y2024_bot3::wpilib
+
+AOS_ROBOT_CLASS(::y2024_bot3::wpilib::WPILibRobot);
diff --git a/y2024_bot3/www/BUILD b/y2024_bot3/www/BUILD
new file mode 100644
index 0000000..51d7c8f
--- /dev/null
+++ b/y2024_bot3/www/BUILD
@@ -0,0 +1,68 @@
+load("//frc971/downloader:downloader.bzl", "aos_downloader_dir")
+load("//tools/build_rules:js.bzl", "rollup_bundle", "ts_project")
+
+filegroup(
+    name = "files",
+    srcs = glob([
+        "**/*.html",
+        "**/*.css",
+        "**/*.png",
+    ]) + ["2024_bot3.png"],
+    visibility = ["//visibility:public"],
+)
+
+genrule(
+    name = "2024_bot3_field_png",
+    srcs = ["//third_party/y2024/field:pictures"],
+    outs = ["2024_bot3.png"],
+    cmd = "cp third_party/y2024/field/2024.png $@",
+)
+
+ts_project(
+    name = "field_main",
+    srcs = [
+        "constants.ts",
+        "field_handler.ts",
+        "field_main.ts",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    deps = [
+        "//aos/network:connect_ts_fbs",
+        "//aos/network:message_bridge_client_ts_fbs",
+        "//aos/network:message_bridge_server_ts_fbs",
+        "//aos/network:web_proxy_ts_fbs",
+        "//aos/network/www:proxy",
+        "//frc971/control_loops:control_loops_ts_fbs",
+        "//frc971/control_loops/drivetrain:drivetrain_can_position_ts_fbs",
+        "//frc971/control_loops/drivetrain:drivetrain_position_ts_fbs",
+        "//frc971/control_loops/drivetrain:drivetrain_status_ts_fbs",
+        "//frc971/control_loops/drivetrain/localization:localizer_output_ts_fbs",
+        "//frc971/vision:target_map_ts_fbs",
+        "//y2024_bot3/control_loops/superstructure:superstructure_position_ts_fbs",
+        "//y2024_bot3/control_loops/superstructure:superstructure_status_ts_fbs",
+        "@com_github_google_flatbuffers//ts:flatbuffers_ts",
+    ],
+)
+
+rollup_bundle(
+    name = "field_main_bundle",
+    entry_point = "field_main.ts",
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//y2024_bot3:__subpackages__"],
+    deps = [
+        ":field_main",
+    ],
+)
+
+aos_downloader_dir(
+    name = "www_files",
+    srcs = [
+        ":field_main_bundle.min.js",
+        ":files",
+        "//frc971/analysis:plot_index_bundle.min.js",
+        "//frc971/www:starter_files",
+    ],
+    dir = "www",
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+)
diff --git a/y2024_bot3/www/constants.ts b/y2024_bot3/www/constants.ts
new file mode 100644
index 0000000..97d6e28
--- /dev/null
+++ b/y2024_bot3/www/constants.ts
@@ -0,0 +1,8 @@
+// Conversion constants to meters
+export const IN_TO_M = 0.0254;
+export const FT_TO_M = 0.3048;
+// Dimensions of the field in meters
+// Numbers are slightly hand-tuned to match the PNG that we are using.
+export const FIELD_WIDTH = 26 * FT_TO_M + 11.25 * IN_TO_M;
+export const FIELD_LENGTH = 54 * FT_TO_M + 3.25 * IN_TO_M;
+
diff --git a/y2024_bot3/www/field.html b/y2024_bot3/www/field.html
new file mode 100644
index 0000000..04fb5c1
--- /dev/null
+++ b/y2024_bot3/www/field.html
@@ -0,0 +1,101 @@
+<html>
+
+<head>
+  <script src="field_main_bundle.min.js" defer></script>
+  <link rel="stylesheet" href="styles.css">
+</head>
+
+<body>
+  <div style="display: grid;
+  grid-template-columns: auto auto auto; gap: 5px;">
+    <div>
+      <div id="field"> </div>
+      <div id="legend"> </div>
+      <h3>Zeroing Faults:</h3>
+      <p id="zeroing_faults"> NA </p>
+    </div>
+    <div>
+      <table>
+        <tr>
+          <th colspan="2" style="text-align: center;">Robot State</th>
+        </tr>
+        <tr>
+          <td>X</td>
+          <td id="x"> NA </td>
+        </tr>
+        <tr>
+          <td>Y</td>
+          <td id="y"> NA </td>
+        </tr>
+        <tr>
+          <td>Theta</td>
+          <td id="theta"> NA </td>
+        </tr>
+      </table>
+      <table>
+        <tr>
+          <th colspan="2" style="text-align: center;">Images</th>
+        </tr>
+        <tr>
+          <td> Images Accepted </td>
+          <td id="images_accepted"> NA </td>
+        </tr>
+      </table>
+      <table>
+        <tr>
+          <th colspan="2" style="text-align: center;">Superstructure States</th>
+        </tr>
+        <tr>
+          <td style="font-weight: bold;">Superstructure State</td>
+          <td id="superstructure_state" style="font-weight: bold;"> NA </td>
+        </tr>
+      </table>
+    </div>
+    <div>
+      <table>
+        <tr>
+          <th colspan="2" style="text-align: center;">Subsystems</th>
+        </tr>
+      </table>
+      <table>
+        <tr>
+          <th colspan="2" style="text-align: center;"> Drivetrain Encoder Positions </th>
+        </tr>
+        <tr>
+          <td> Left Encoder Position</td>
+          <td id="left_drivetrain_encoder"> NA </td>
+        </tr>
+        <tr>
+          <td> Right Encoder Position</td>
+          <td id="right_drivetrain_encoder"> NA </td>
+        </tr>
+        <tr>
+          <td> Right Front Falcon CAN Position</td>
+          <td id="falcon_right_front"> NA </td>
+        </tr>
+        <tr>
+          <td> Right Back Falcon CAN Position</td>
+          <td id="falcon_right_back"> NA </td>
+        </tr>
+        <tr>
+          <td> Left Front Falcon CAN Position</td>
+          <td id="falcon_left_front"> NA </td>
+        </tr>
+        <tr>
+          <td> Left Back Falcon CAN Position</td>
+          <td id="falcon_left_back"> NA </td>
+        </tr>
+      </table>
+    </div>
+  </div>
+  <div id="message_bridge_status">
+    <div>
+      <div>Node</div>
+      <div>Client</div>
+      <div>Server</div>
+    </div>
+  </div>
+  <div id="vision_readouts"> </div>
+</body>
+
+</html>
\ No newline at end of file
diff --git a/y2024_bot3/www/field_handler.ts b/y2024_bot3/www/field_handler.ts
new file mode 100644
index 0000000..5b243ef
--- /dev/null
+++ b/y2024_bot3/www/field_handler.ts
@@ -0,0 +1,347 @@
+import {ByteBuffer} from 'flatbuffers'
+import {ClientStatistics} from '../../aos/network/message_bridge_client_generated'
+import {ServerStatistics, State as ConnectionState} from '../../aos/network/message_bridge_server_generated'
+import {Connection} from '../../aos/network/www/proxy'
+import {ZeroingError} from '../../frc971/control_loops/control_loops_generated'
+import {Position as DrivetrainPosition} from '../../frc971/control_loops/drivetrain/drivetrain_position_generated'
+import {CANPosition as DrivetrainCANPosition} from '../../frc971/control_loops/drivetrain/drivetrain_can_position_generated'
+import {Status as DrivetrainStatus} from '../../frc971/control_loops/drivetrain/drivetrain_status_generated'
+import {Position as SuperstructurePosition} from  '../control_loops/superstructure/superstructure_position_generated'
+import {Status as SuperstructureStatus} from '../control_loops/superstructure/superstructure_status_generated'
+import {TargetMap} from '../../frc971/vision/target_map_generated'
+
+
+import {FIELD_LENGTH, FIELD_WIDTH, FT_TO_M, IN_TO_M} from './constants';
+
+// (0,0) is field center, +X is toward red DS
+const FIELD_SIDE_Y = FIELD_WIDTH / 2;
+const FIELD_EDGE_X = FIELD_LENGTH / 2;
+
+const ROBOT_WIDTH = 29 * IN_TO_M;
+const ROBOT_LENGTH = 32 * IN_TO_M;
+
+const CAMERA_COLORS = ['#ff00ff', '#ffff00', '#00ffff', '#ffa500'];
+const CAMERAS = ['/orin1/camera0', '/orin1/camera1', '/imu/camera0', '/imu/camera1'];
+
+export class FieldHandler {
+  private canvas = document.createElement('canvas');
+  private superstructureStatus: SuperstructureStatus|null = null;
+  private superstructurePosition: SuperstructurePosition|null = null;
+
+  // Image information indexed by timestamp (seconds since the epoch), so that
+  // we can stop displaying images after a certain amount of time.
+  private x: HTMLElement = (document.getElementById('x') as HTMLElement);
+  private y: HTMLElement = (document.getElementById('y') as HTMLElement);
+  private theta: HTMLElement =
+      (document.getElementById('theta') as HTMLElement);
+
+  private imagesAcceptedCounter: HTMLElement =
+      (document.getElementById('images_accepted') as HTMLElement);
+  // HTML elements for rejection reasons for individual cameras. Indices
+  // corresponding to RejectionReason enum values will be for those reasons. The
+  // final row will account for images rejected by the aprilrobotics detector
+  // instead of the localizer.
+  private rejectionReasonCells: HTMLElement[][] = [];
+  private messageBridgeDiv: HTMLElement =
+      (document.getElementById('message_bridge_status') as HTMLElement);
+  private clientStatuses = new Map<string, HTMLElement>();
+  private serverStatuses = new Map<string, HTMLElement>();
+
+  private fieldImage: HTMLImageElement = new Image();
+
+  private zeroingFaults: HTMLElement =
+      (document.getElementById('zeroing_faults') as HTMLElement);
+
+  private leftDrivetrainEncoder: HTMLElement =
+      (document.getElementById('left_drivetrain_encoder') as HTMLElement);
+  private rightDrivetrainEncoder: HTMLElement =
+      (document.getElementById('right_drivetrain_encoder') as HTMLElement);
+  private falconRightFrontPosition: HTMLElement =
+      (document.getElementById('falcon_right_front') as HTMLElement);
+  private falconRightBackPosition: HTMLElement =
+      (document.getElementById('falcon_right_back') as HTMLElement);
+  private falconLeftFrontPosition: HTMLElement =
+      (document.getElementById('falcon_left_front') as HTMLElement);
+  private falconLeftBackPosition: HTMLElement =
+      (document.getElementById('falcon_left_back') as HTMLElement);
+
+  constructor(private readonly connection: Connection) {
+    (document.getElementById('field') as HTMLElement).appendChild(this.canvas);
+
+    this.fieldImage.src = '2024.png';
+
+    // Construct a table header.
+    {
+      const row = document.createElement('div');
+      const nameCell = document.createElement('div');
+      nameCell.innerHTML = 'Rejection Reason';
+      row.appendChild(nameCell);
+      for (const camera of CAMERAS) {
+        const nodeCell = document.createElement('div');
+        nodeCell.innerHTML = camera;
+        row.appendChild(nodeCell);
+      }
+      document.getElementById('vision_readouts').appendChild(row);
+    }
+
+    // Add rejection reason row for aprilrobotics rejections.
+    {
+      const row = document.createElement('div');
+      const nameCell = document.createElement('div');
+      nameCell.innerHTML = 'Rejected by aprilrobotics';
+      row.appendChild(nameCell);
+      this.rejectionReasonCells.push([]);
+      for (const camera of CAMERAS) {
+        const valueCell = document.createElement('div');
+        valueCell.innerHTML = 'NA';
+        this.rejectionReasonCells[this.rejectionReasonCells.length - 1].push(
+            valueCell);
+        row.appendChild(valueCell);
+      }
+      document.getElementById('vision_readouts').appendChild(row);
+    }
+
+    for (let ii = 0; ii < CAMERA_COLORS.length; ++ii) {
+      const legendEntry = document.createElement('div');
+      legendEntry.style.color = CAMERA_COLORS[ii];
+      legendEntry.innerHTML = CAMERAS[ii];
+      document.getElementById('legend').appendChild(legendEntry);
+    }
+
+    this.connection.addConfigHandler(() => {
+      // Visualization message is reliable so that we can see *all* the vision
+      // matches.
+     
+      for (const camera in CAMERAS) {
+        // Make unreliable to reduce network spam.
+        this.connection.addHandler(
+          CAMERAS[camera], 'frc971.vision.TargetMap', (data) => {
+              this.handleCameraTargetMap(camera, data);
+            });
+      }
+
+      this.connection.addHandler(
+        '/superstructure', "y2024_bot3.control_loops.superstructure.Status",
+        (data) => {
+          this.handleSuperstructureStatus(data)
+          });
+      this.connection.addHandler(
+        '/superstructure', "y2024_bot3.control_loops.superstructure.Positon",
+        (data) => {
+          this.handleSuperstructurePosition(data)
+          });
+      this.connection.addHandler(
+        '/aos', 'aos.message_bridge.ServerStatistics',
+        (data) => {this.handleServerStatistics(data)});
+      this.connection.addHandler(
+        '/aos', 'aos.message_bridge.ClientStatistics',
+        (data) => {this.handleClientStatistics(data)});
+      });
+  }
+  private handleCameraTargetMap(pi: string, data: Uint8Array): void {
+    const fbBuffer = new ByteBuffer(data);
+    const targetMap = TargetMap.getRootAsTargetMap(fbBuffer);
+    this.rejectionReasonCells[this.rejectionReasonCells.length - 1][pi]
+        .innerHTML = targetMap.rejections().toString();
+  }
+
+  private handleSuperstructureStatus(data: Uint8Array): void {
+	  const fbBuffer = new ByteBuffer(data);
+	  this.superstructureStatus = SuperstructureStatus.getRootAsStatus(fbBuffer);
+  }
+
+  private handleSuperstructurePosition(data: Uint8Array): void {
+	  const fbBuffer = new ByteBuffer(data);
+	  this.superstructurePosition = SuperstructurePosition.getRootAsPosition(fbBuffer);
+  }
+
+  private populateNodeConnections(nodeName: string): void {
+    const row = document.createElement('div');
+    this.messageBridgeDiv.appendChild(row);
+    const nodeDiv = document.createElement('div');
+    nodeDiv.innerHTML = nodeName;
+    row.appendChild(nodeDiv);
+    const clientDiv = document.createElement('div');
+    clientDiv.innerHTML = 'N/A';
+    row.appendChild(clientDiv);
+    const serverDiv = document.createElement('div');
+    serverDiv.innerHTML = 'N/A';
+    row.appendChild(serverDiv);
+    this.serverStatuses.set(nodeName, serverDiv);
+    this.clientStatuses.set(nodeName, clientDiv);
+  }
+
+  private setCurrentNodeState(element: HTMLElement, state: ConnectionState):
+      void {
+    if (state === ConnectionState.CONNECTED) {
+      element.innerHTML = ConnectionState[state];
+      element.classList.remove('faulted');
+      element.classList.add('connected');
+    } else {
+      element.innerHTML = ConnectionState[state];
+      element.classList.remove('connected');
+      element.classList.add('faulted');
+    }
+  }
+
+  private handleServerStatistics(data: Uint8Array): void {
+    const fbBuffer = new ByteBuffer(data);
+    const serverStatistics =
+        ServerStatistics.getRootAsServerStatistics(fbBuffer);
+
+    for (let ii = 0; ii < serverStatistics.connectionsLength(); ++ii) {
+      const connection = serverStatistics.connections(ii);
+      const nodeName = connection.node().name();
+      if (!this.serverStatuses.has(nodeName)) {
+        this.populateNodeConnections(nodeName);
+      }
+      this.setCurrentNodeState(
+          this.serverStatuses.get(nodeName), connection.state());
+    }
+  }
+
+  private handleClientStatistics(data: Uint8Array): void {
+    const fbBuffer = new ByteBuffer(data);
+    const clientStatistics =
+        ClientStatistics.getRootAsClientStatistics(fbBuffer);
+
+    for (let ii = 0; ii < clientStatistics.connectionsLength(); ++ii) {
+      const connection = clientStatistics.connections(ii);
+      const nodeName = connection.node().name();
+      if (!this.clientStatuses.has(nodeName)) {
+        this.populateNodeConnections(nodeName);
+      }
+      this.setCurrentNodeState(
+          this.clientStatuses.get(nodeName), connection.state());
+    }
+  }
+
+  drawField(): void {
+    const ctx = this.canvas.getContext('2d');
+    ctx.save();
+    ctx.scale(1.0, -1.0);
+    ctx.drawImage(
+        this.fieldImage, 0, 0, this.fieldImage.width, this.fieldImage.height,
+        -FIELD_EDGE_X, -FIELD_SIDE_Y, FIELD_LENGTH, FIELD_WIDTH);
+    ctx.restore();
+  }
+
+  drawCamera(x: number, y: number, theta: number, color: string = 'blue'):
+  void {
+    const ctx = this.canvas.getContext('2d');
+    ctx.save();
+    ctx.translate(x, y);
+    ctx.rotate(theta);
+    ctx.strokeStyle = color;
+    ctx.beginPath();
+    ctx.moveTo(0.5, 0.5);
+    ctx.lineTo(0, 0);
+    ctx.lineTo(0.5, -0.5);
+    ctx.stroke();
+    ctx.beginPath();
+    ctx.arc(0, 0, 0.25, -Math.PI / 4, Math.PI / 4);
+    ctx.stroke();
+    ctx.restore();
+  }
+
+  drawRobot(
+    x: number, y: number, theta: number, color: string = 'blue',
+    dashed: boolean = false): void {
+  const ctx = this.canvas.getContext('2d');
+  ctx.save();
+  ctx.translate(x, y);
+  ctx.rotate(theta);
+  ctx.strokeStyle = color;
+  ctx.lineWidth = ROBOT_WIDTH / 10.0;
+  if (dashed) {
+    ctx.setLineDash([0.05, 0.05]);
+  } else {
+    // Empty array = solid line.
+    ctx.setLineDash([]);
+  }
+  ctx.rect(-ROBOT_LENGTH / 2, -ROBOT_WIDTH / 2, ROBOT_LENGTH, ROBOT_WIDTH);
+  ctx.stroke();
+
+  // Draw line indicating which direction is forwards on the robot.
+  ctx.beginPath();
+  ctx.moveTo(0, 0);
+  ctx.lineTo(ROBOT_LENGTH / 2.0, 0);
+  ctx.stroke();
+
+  ctx.restore();
+}
+
+  setZeroing(div: HTMLElement): void {
+    div.innerHTML = 'zeroing';
+    div.classList.remove('faulted');
+    div.classList.add('zeroing');
+    div.classList.remove('near');
+  }
+
+  setEstopped(div: HTMLElement): void {
+    div.innerHTML = 'estopped';
+    div.classList.add('faulted');
+    div.classList.remove('zeroing');
+    div.classList.remove('near');
+  }
+
+  setTargetValue(
+      div: HTMLElement, target: number, val: number, tolerance: number): void {
+    div.innerHTML = val.toFixed(4);
+    div.classList.remove('faulted');
+    div.classList.remove('zeroing');
+    if (Math.abs(target - val) < tolerance) {
+      div.classList.add('near');
+    } else {
+      div.classList.remove('near');
+    }
+  }
+
+  setValue(div: HTMLElement, val: number): void {
+    div.innerHTML = val.toFixed(4);
+    div.classList.remove('faulted');
+    div.classList.remove('zeroing');
+    div.classList.remove('near');
+  }
+
+  setBoolean(div: HTMLElement, triggered: boolean): void {
+    div.innerHTML = ((triggered) ? "TRUE" : "FALSE")
+    div.className = '';
+    if (triggered) {
+      div.classList.add('lightgreen');
+    } else {
+      div.classList.add('lightcoral');
+    }
+  }
+
+  draw(): void {
+    this.reset();
+    this.drawField();
+
+    window.requestAnimationFrame(() => this.draw());
+  }
+
+  reset(): void {
+    const ctx = this.canvas.getContext('2d');
+    // Empty space from the canvas boundary to the image
+    const IMAGE_PADDING = 10;
+    ctx.setTransform(1, 0, 0, 1, 0, 0);
+    const size = window.innerHeight * 0.9;
+    ctx.canvas.height = size;
+    const width = size / 2 + 20;
+    ctx.canvas.width = width;
+    ctx.clearRect(0, 0, size, width);
+
+    // Translate to center of display.
+    ctx.translate(width / 2, size / 2);
+    // Coordinate system is:
+    // x -> forward.
+    // y -> to the left.
+    ctx.rotate(-Math.PI / 2);
+    ctx.scale(1, -1);
+
+    const M_TO_PX = (size - IMAGE_PADDING) / FIELD_LENGTH;
+    ctx.scale(M_TO_PX, M_TO_PX);
+    ctx.lineWidth = 1 / M_TO_PX;
+  }
+}
diff --git a/y2024_bot3/www/field_main.ts b/y2024_bot3/www/field_main.ts
new file mode 100644
index 0000000..ef8b99d
--- /dev/null
+++ b/y2024_bot3/www/field_main.ts
@@ -0,0 +1,11 @@
+import {Connection} from '../../aos/network/www/proxy';
+
+import {FieldHandler} from './field_handler';
+
+const conn = new Connection();
+
+conn.connect();
+
+const fieldHandler = new FieldHandler(conn);
+
+fieldHandler.draw();
diff --git a/y2024_bot3/www/index.html b/y2024_bot3/www/index.html
new file mode 100644
index 0000000..98ecf42
--- /dev/null
+++ b/y2024_bot3/www/index.html
@@ -0,0 +1,7 @@
+<html>
+  <body>
+    <a href="field.html">Field Visualization</a><br>
+    <a href="plotter.html">Plots</a><br>
+    <a href="starter.html">AOS Starter Status</a>
+  </body>
+</html>
diff --git a/y2024_bot3/www/plotter.html b/y2024_bot3/www/plotter.html
new file mode 100644
index 0000000..86f5aa8
--- /dev/null
+++ b/y2024_bot3/www/plotter.html
@@ -0,0 +1,8 @@
+<html>
+  <head>
+    <script src="plot_index_bundle.min.js" defer></script>
+    <link rel="stylesheet" href="styles.css">
+  </head>
+  <body>
+  </body>
+</html>
diff --git a/y2024_bot3/y2024_bot3.json b/y2024_bot3/y2024_bot3.json
new file mode 100644
index 0000000..aea954c
--- /dev/null
+++ b/y2024_bot3/y2024_bot3.json
@@ -0,0 +1,19 @@
+{
+  "channel_storage_duration": 10000000000,
+  "maps": [
+    {
+      "match": {
+        "name": "/aos",
+        "type": "aos.RobotState"
+      },
+      "rename": {
+        "name": "/roborio/aos"
+      }
+    }
+  ],
+  "imports": [
+    "y2024_bot3_roborio.json",
+    "y2024_bot3_imu.json",
+    "y2024_bot3_orin1.json",
+  ]
+}
diff --git a/y2024_bot3/y2024_bot3_imu.json b/y2024_bot3/y2024_bot3_imu.json
new file mode 100644
index 0000000..9473c59
--- /dev/null
+++ b/y2024_bot3/y2024_bot3_imu.json
@@ -0,0 +1,547 @@
+{
+  "channels": [
+    {
+      "name": "/imu/aos",
+      "type": "aos.util.FilesystemStatus",
+      "source_node": "imu",
+      "frequency": 2
+    },
+    {
+      "name": "/imu/aos",
+      "type": "aos.JoystickState",
+      "source_node": "imu",
+      "frequency": 100,
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "orin1"
+      ],
+      "destination_nodes": [
+        {
+          "name": "orin1",
+          "priority": 5,
+          "time_to_live": 50000000,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "imu"
+          ]
+        }
+      ]
+    },
+    {
+      "name": "/imu/aos/remote_timestamps/orin1/imu/aos/aos-JoystickState",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "imu",
+      "logger": "NOT_LOGGED",
+      "frequency": 300,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
+      "name": "/imu/aos",
+      "type": "aos.timing.Report",
+      "source_node": "imu",
+      "frequency": 50,
+      "num_senders": 30,
+      "max_size": 10912
+    },
+    {
+      "name": "/imu/aos",
+      "type": "aos.logging.LogMessageFbs",
+      "source_node": "imu",
+      "frequency": 200,
+      "num_senders": 30
+    },
+    {
+      "name": "/imu/aos",
+      "type": "aos.starter.Status",
+      "source_node": "imu",
+      "frequency": 50,
+      "num_senders": 20,
+      "max_size": 6144
+    },
+    {
+      "name": "/imu/aos",
+      "type": "aos.starter.StarterRpc",
+      "source_node": "imu",
+      "frequency": 10,
+      "num_senders": 2
+    },
+    {
+      "name": "/imu/aos",
+      "type": "aos.message_bridge.ServerStatistics",
+      "source_node": "imu",
+      "max_size": 2048,
+      "frequency": 10,
+      "num_senders": 2
+    },
+    {
+      "name": "/imu/aos",
+      "type": "aos.message_bridge.ClientStatistics",
+      "source_node": "imu",
+      "frequency": 20,
+      "num_senders": 2
+    },
+    {
+      "name": "/imu/aos",
+      "type": "aos.logging.DynamicLogCommand",
+      "source_node": "imu",
+      "frequency": 10,
+      "num_senders": 2
+    },
+    {
+      "name": "/imu/aos",
+      "type": "aos.message_bridge.Timestamp",
+      "source_node": "imu",
+      "frequency": 15,
+      "num_senders": 2,
+      "logger_nodes": [
+        "roborio"
+      ],
+      "max_size": 400,
+      "destination_nodes": [
+        {
+          "name": "roborio",
+          "priority": 1,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "imu"
+          ],
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/imu/aos/remote_timestamps/roborio/imu/aos/aos-message_bridge-Timestamp",
+      "type": "aos.message_bridge.RemoteMessage",
+      "frequency": 20,
+      "source_node": "imu",
+      "max_size": 208
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "aos.starter.StarterRpc",
+      "source_node": "roborio",
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "imu"
+      ],
+      "destination_nodes": [
+        {
+          "name": "imu",
+          "priority": 5,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "roborio"
+          ],
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/roborio/aos/remote_timestamps/imu/roborio/aos/aos-starter-StarterRpc",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "roborio",
+      "logger": "NOT_LOGGED",
+      "frequency": 20,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
+      "name": "/imu/camera0",
+      "type": "frc971.vision.CameraImage",
+      "source_node": "imu",
+      "channel_storage_duration": 1000000000,
+      "frequency": 70,
+      "max_size": 4752384,
+      "num_readers": 6,
+      "read_method": "PIN",
+      "num_senders": 18
+    },
+    {
+      "name": "/imu/camera1",
+      "type": "frc971.vision.CameraImage",
+      "source_node": "imu",
+      "channel_storage_duration": 1000000000,
+      "frequency": 70,
+      "max_size": 4752384,
+      "num_readers": 6,
+      "read_method": "PIN",
+      "num_senders": 18
+    },
+    {
+      "name": "/imu/camera0",
+      "type": "foxglove.CompressedImage",
+      "source_node": "imu",
+      "logger": "NOT_LOGGED",
+      "channel_storage_duration": 1000000000,
+      "frequency": 70,
+      "max_size": 622384
+    },
+    {
+      "name": "/imu/camera1",
+      "type": "foxglove.CompressedImage",
+      "source_node": "imu",
+      "logger": "NOT_LOGGED",
+      "channel_storage_duration": 1000000000,
+      "frequency": 70,
+      "max_size": 622384
+    },
+    {
+      "name": "/imu/camera0",
+      "type": "foxglove.ImageAnnotations",
+      "source_node": "imu",
+      "frequency": 70,
+      "max_size": 50000
+    },
+    {
+      "name": "/imu/camera1",
+      "type": "foxglove.ImageAnnotations",
+      "source_node": "imu",
+      "frequency": 70,
+      "max_size": 50000
+    },
+    {
+      "name": "/imu/camera0",
+      "type": "frc971.vision.TargetMap",
+      "source_node": "imu",
+      "frequency": 70,
+      "num_senders": 2,
+      "max_size": 1024
+    },
+    {
+      "name": "/imu/camera1",
+      "type": "frc971.vision.TargetMap",
+      "source_node": "imu",
+      "frequency": 70,
+      "num_senders": 2,
+      "max_size": 1024
+    },
+    {
+      "name": "/imu",
+      "type": "frc971.imu.DualImu",
+      "source_node": "imu",
+      "frequency": 1100,
+      "num_senders": 1,
+      "max_size": 496
+    },
+    {
+      "name": "/imu",
+      "type": "frc971.imu.CanTranslatorStatus",
+      "source_node": "imu",
+      "frequency": 1000,
+      "num_senders": 1,
+      "max_size": 200
+    },
+    {
+      "name": "/can/cana",
+      "type": "frc971.can_logger.CanFrame",
+      "source_node": "imu",
+      "frequency": 9000,
+      "channel_storage_duration": 7000000000,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
+      "name": "/imu",
+      "type": "frc971.imu.DualImuBlenderStatus",
+      "source_node": "imu",
+      "frequency": 1100,
+      "num_senders": 1,
+      "max_size": 200
+    },
+    {
+      "name": "/imu/hardware_monitor",
+      "type": "frc971.orin.HardwareStats",
+      "source_node": "imu",
+      "frequency": 2
+    },
+    {
+      "name": "/imu/constants",
+      "type": "y2024_bot3.Constants",
+      "source_node": "imu",
+      "frequency": 1,
+      "num_senders": 2,
+      "max_size": 65536
+    }
+  ],
+  "applications": [
+    {
+      "name": "message_bridge_client",
+      "args": [
+        "--rt_priority=16",
+        "--sinit_max_init_timeout=5000",
+        "--rmem=8388608"
+      ],
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "irq_affinity",
+      "executable_name": "irq_affinity",
+      "user": "root",
+      "args": ["--user=pi", "--irq_config=orin_irq_config.json"],
+      "nodes": [
+          "imu"
+      ]
+    },
+    {
+      "name": "filesystem_monitor",
+      "executable_name": "filesystem_monitor",
+      "nodes": [
+          "imu"
+      ]
+    },
+    {
+      "name": "hardware_monitor",
+      "executable_name": "hardware_monitor",
+      "nodes": [
+          "imu"
+      ]
+    },
+    {
+      "name": "joystick_republish",
+      "executable_name": "joystick_republish",
+      "user": "pi",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "message_bridge_server",
+      "executable_name": "message_bridge_server",
+      "user": "pi",
+      "args": [
+        "--rt_priority=16",
+        "--force_wmem_max=131072"
+      ],
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "imu_can_logger",
+      "executable_name": "can_logger",
+      "args": [
+        "--priority=59",
+        "--affinity=5"
+      ],
+      "nodes": [
+        "imu"
+      ]
+    },
+    // TODO(max): Update the channel value with whatever channel the IMU is on.
+    {
+      "name": "can_translator",
+      "executable_name": "can_translator",
+      "args": [
+          "--channel=/can/cana"
+      ],
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "dual_imu_blender",
+      "executable_name": "dual_imu_blender",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "web_proxy",
+      "executable_name": "web_proxy_main",
+      "args": [
+        "--min_ice_port=5800",
+        "--max_ice_port=5810"
+      ],
+      "user": "pi",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "foxglove_websocket",
+      "user": "pi",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "constants_sender",
+      "autorestart": false,
+      "user": "pi",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "image_logger",
+      "executable_name": "image_logger",
+      "args": [
+        "--rotate_every",
+        "30.0",
+        "--direct",
+        "--flush_size=4194304"
+      ],
+      "user": "pi",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "foxglove_websocket",
+      "user": "pi",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "foxglove_image_converter0",
+      "executable_name": "foxglove_image_converter",
+      "user": "pi",
+      "args": [
+          "--channel", "/camera0"
+      ],
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "foxglove_image_converter1",
+      "executable_name": "foxglove_image_converter",
+      "user": "pi",
+      "args": [
+          "--channel", "/camera1"
+      ],
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "constants_sender",
+      "autorestart": false,
+      "user": "pi",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "argus_monitor_imu",
+      "executable_name": "argus_monitor",
+      "args": [
+        "/imu/camera0",
+        "frc971.vision.TargetMap",
+        "/imu/camera1",
+        "frc971.vision.TargetMap",
+      ],
+      "user": "pi",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "argus_camera0",
+      "executable_name": "argus_camera",
+      "args": [
+          "--camera=0",
+          "--channel=/camera0"
+      ],
+      "user": "pi",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "argus_camera1",
+      "executable_name": "argus_camera",
+      "args": [
+          "--camera=1",
+          "--channel=/camera1"
+      ],
+      "user": "pi",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "apriltag_detector0",
+      "executable_name": "apriltag_detector",
+      "args": [
+          "--channel=/camera0"
+      ],
+      "user": "pi",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "apriltag_detector1",
+      "executable_name": "apriltag_detector",
+      "args": [
+          "--channel=/camera1"
+      ],
+      "user": "pi",
+      "nodes": [
+        "imu"
+      ]
+    }
+  ],
+  "maps": [
+    {
+      "match": {
+        "name": "/constants*",
+        "source_node": "imu"
+      },
+      "rename": {
+        "name": "/imu/constants"
+      }
+    },
+    {
+      "match": {
+        "name": "/aos*",
+        "source_node": "imu"
+      },
+      "rename": {
+        "name": "/imu/aos"
+      }
+    },
+    {
+      "match": {
+        "name": "/camera*",
+        "source_node": "imu"
+      },
+      "rename": {
+        "name": "/imu/camera"
+      }
+    },
+    {
+      "match": {
+        "name": "/hardware_monitor*",
+        "source_node": "imu"
+      },
+      "rename": {
+        "name": "/imu/hardware_monitor"
+      }
+    }
+  ],
+  "nodes": [
+    {
+      "name": "imu",
+      "hostname": "orin2",
+      "hostnames": [
+        "orin-971-2",
+        "orin-7971-2",
+        "orin-8971-2",
+        "orin-9971-2"
+      ],
+      "port": 9971
+    },
+    {
+      "name": "roborio"
+    },
+    {
+      "name": "orin1"
+    }
+  ]
+}
diff --git a/y2024_bot3/y2024_bot3_orin1.json b/y2024_bot3/y2024_bot3_orin1.json
new file mode 100644
index 0000000..8d5085e
--- /dev/null
+++ b/y2024_bot3/y2024_bot3_orin1.json
@@ -0,0 +1,493 @@
+{
+  "channels": [
+    {
+      "name": "/orin1/aos",
+      "type": "aos.util.FilesystemStatus",
+      "source_node": "orin1",
+      "frequency": 2
+    },
+    {
+      "name": "/orin1/aos",
+      "type": "aos.timing.Report",
+      "source_node": "orin1",
+      "frequency": 50,
+      "num_senders": 30,
+      "max_size": 8192
+    },
+    {
+      "name": "/orin1/aos",
+      "type": "aos.logging.LogMessageFbs",
+      "source_node": "orin1",
+      "frequency": 200,
+      "num_senders": 30
+    },
+    {
+      "name": "/orin1/aos",
+      "type": "aos.starter.Status",
+      "source_node": "orin1",
+      "frequency": 50,
+      "num_senders": 20,
+      "max_size": 4096
+    },
+    {
+      "name": "/orin1/aos",
+      "type": "aos.starter.StarterRpc",
+      "source_node": "orin1",
+      "frequency": 10,
+      "num_senders": 2
+    },
+    {
+      "name": "/orin1/aos",
+      "type": "aos.message_bridge.ServerStatistics",
+      "source_node": "orin1",
+      "max_size": 2048,
+      "frequency": 10,
+      "num_senders": 2
+    },
+    {
+      "name": "/orin1/aos",
+      "type": "aos.message_bridge.ClientStatistics",
+      "source_node": "orin1",
+      "frequency": 20,
+      "num_senders": 2
+    },
+    {
+      "name": "/orin1/aos",
+      "type": "aos.logging.DynamicLogCommand",
+      "source_node": "orin1",
+      "frequency": 10,
+      "num_senders": 2
+    },
+    {
+      "name": "/orin1/aos",
+      "type": "aos.message_bridge.Timestamp",
+      "source_node": "orin1",
+      "frequency": 15,
+      "num_senders": 2,
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "imu"
+      ],
+      "max_size": 200,
+      "destination_nodes": [
+        {
+          "name": "imu",
+          "priority": 1,
+          "time_to_live": 5000000,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "orin1"
+          ]
+        }
+      ]
+    },
+    {
+      "name": "/orin1/aos/remote_timestamps/imu/orin1/aos/aos-message_bridge-Timestamp",
+      "type": "aos.message_bridge.RemoteMessage",
+      "frequency": 20,
+      "source_node": "orin1",
+      "max_size": 208
+    },
+    {
+      "name": "/imu/aos",
+      "type": "aos.message_bridge.Timestamp",
+      "source_node": "imu",
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "orin1"
+      ],
+      "destination_nodes": [
+        {
+          "name": "orin1",
+          "priority": 1,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "imu"
+          ],
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/imu/aos/remote_timestamps/orin1/imu/aos/aos-message_bridge-Timestamp",
+      "type": "aos.message_bridge.RemoteMessage",
+      "frequency": 20,
+      "source_node": "imu",
+      "max_size": 208
+    },
+    {
+      "name": "/orin1/camera0",
+      "type": "frc971.vision.CameraImage",
+      "source_node": "orin1",
+      "channel_storage_duration": 1000000000,
+      "frequency": 70,
+      "max_size": 4752384,
+      "num_readers": 6,
+      "read_method": "PIN",
+      "num_senders": 18
+    },
+    {
+      "name": "/orin1/camera1",
+      "type": "frc971.vision.CameraImage",
+      "source_node": "orin1",
+      "channel_storage_duration": 1000000000,
+      "frequency": 70,
+      "max_size": 4752384,
+      "num_readers": 6,
+      "read_method": "PIN",
+      "num_senders": 18
+    },
+    {
+      "name": "/orin1/camera0",
+      "type": "foxglove.CompressedImage",
+      "source_node": "orin1",
+      "logger": "NOT_LOGGED",
+      "channel_storage_duration": 1000000000,
+      "frequency": 70,
+      "max_size": 622384
+    },
+    {
+      "name": "/orin1/camera1",
+      "type": "foxglove.CompressedImage",
+      "source_node": "orin1",
+      "logger": "NOT_LOGGED",
+      "channel_storage_duration": 1000000000,
+      "frequency": 70,
+      "max_size": 622384
+    },
+    {
+      "name": "/orin1/camera0",
+      "type": "foxglove.ImageAnnotations",
+      "source_node": "orin1",
+      "frequency": 70,
+      "max_size": 50000
+    },
+    {
+      "name": "/orin1/camera1",
+      "type": "foxglove.ImageAnnotations",
+      "source_node": "orin1",
+      "frequency": 70,
+      "max_size": 50000
+    },
+    {
+      "name": "/orin1/camera0",
+      "type": "frc971.vision.TargetMap",
+      "source_node": "orin1",
+      "frequency": 70,
+      "num_senders": 2,
+      "max_size": 1024,
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "imu"
+      ],
+      "destination_nodes": [
+        {
+          "name": "imu",
+          "priority": 4,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "orin1"
+          ],
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/orin1/camera1",
+      "type": "frc971.vision.TargetMap",
+      "source_node": "orin1",
+      "frequency": 70,
+      "num_senders": 2,
+      "max_size": 1024,
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "imu"
+      ],
+      "destination_nodes": [
+        {
+          "name": "imu",
+          "priority": 4,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "orin1"
+          ],
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/orin1/aos/remote_timestamps/imu/orin1/camera0/frc971-vision-TargetMap",
+      "type": "aos.message_bridge.RemoteMessage",
+      "frequency": 80,
+      "source_node": "orin1",
+      "max_size": 208
+    },
+    {
+      "name": "/orin1/aos/remote_timestamps/imu/orin1/camera1/frc971-vision-TargetMap",
+      "type": "aos.message_bridge.RemoteMessage",
+      "frequency": 80,
+      "source_node": "orin1",
+      "max_size": 208
+    },
+    {
+      "name": "/orin1/hardware_monitor",
+      "type": "frc971.orin.HardwareStats",
+      "source_node": "orin1",
+      "frequency": 2
+    },
+    {
+      "name": "/orin1/constants",
+      "type": "y2024_bot3.Constants",
+      "source_node": "orin1",
+      "frequency": 1,
+      "num_senders": 2,
+      "max_size": 65536
+    }
+  ],
+  "applications": [
+    {
+      "name": "message_bridge_client",
+      "executable_name": "message_bridge_client",
+      "args": [
+        "--rt_priority=16",
+        "--sinit_max_init_timeout=5000",
+        "--rmem=8388608"
+      ],
+      "user": "pi",
+      "nodes": [
+        "orin1"
+      ]
+    },
+    {
+      "name": "irq_affinity",
+      "executable_name": "irq_affinity",
+      "user": "root",
+      "args": ["--user=pi", "--irq_config=orin_irq_config.json"],
+      "nodes": [
+          "orin1"
+      ]
+    },
+    {
+      "name": "filesystem_monitor",
+      "executable_name": "filesystem_monitor",
+      "nodes": [
+          "orin1"
+      ]
+    },
+    {
+      "name": "hardware_monitor",
+      "executable_name": "hardware_monitor",
+      "nodes": [
+          "orin1"
+      ]
+    },
+    {
+      "name": "message_bridge_server",
+      "executable_name": "message_bridge_server",
+       "args": [
+         "--rt_priority=16",
+         "--force_wmem_max=131072"
+       ],
+      "user": "pi",
+      "nodes": [
+        "orin1"
+      ]
+    },
+    {
+      "name": "web_proxy",
+      "executable_name": "web_proxy_main",
+      "user": "pi",
+      "args": [
+        "--min_ice_port=5800",
+        "--max_ice_port=5810"
+      ],
+      "nodes": [
+        "orin1"
+      ]
+    },
+    {
+      "name": "image_logger",
+      "executable_name": "image_logger",
+      "args": [
+        "--rotate_every",
+        "30.0",
+        "--direct",
+        "--flush_size=4194304"
+      ],
+      "user": "pi",
+      "nodes": [
+        "orin1"
+      ]
+    },
+    {
+      "name": "foxglove_websocket",
+      "user": "pi",
+      "nodes": [
+        "orin1"
+      ]
+    },
+    {
+      "name": "foxglove_image_converter0",
+      "executable_name": "foxglove_image_converter",
+      "user": "pi",
+      "args": [
+          "--channel", "/camera0"
+      ],
+      "nodes": [
+        "orin1"
+      ]
+    },
+    {
+      "name": "foxglove_image_converter1",
+      "executable_name": "foxglove_image_converter",
+      "user": "pi",
+      "args": [
+          "--channel", "/camera1"
+      ],
+      "nodes": [
+        "orin1"
+      ]
+    },
+    {
+      "name": "constants_sender",
+      "autorestart": false,
+      "user": "pi",
+      "nodes": [
+        "orin1"
+      ]
+    },
+    {
+      "name": "argus_monitor_orin1",
+      "executable_name": "argus_monitor",
+      "args": [
+        "/orin1/camera0",
+        "frc971.vision.TargetMap",
+        "/orin1/camera1",
+        "frc971.vision.TargetMap",
+      ],
+      "user": "pi",
+      "nodes": [
+        "orin1"
+      ]
+    },
+    {
+      "name": "argus_camera0",
+      "executable_name": "argus_camera",
+      "args": [
+          "--camera=0",
+          "--channel=/camera0"
+      ],
+      "user": "pi",
+      "nodes": [
+        "orin1"
+      ]
+    },
+    {
+      "name": "argus_camera1",
+      "executable_name": "argus_camera",
+      "args": [
+          "--camera=1",
+          "--channel=/camera1"
+      ],
+      "user": "pi",
+      "nodes": [
+        "orin1"
+      ]
+    },
+    {
+      "name": "apriltag_detector0",
+      "executable_name": "apriltag_detector",
+      "args": [
+          "--channel=/camera0"
+      ],
+      "user": "pi",
+      "nodes": [
+        "orin1"
+      ]
+    },
+    {
+      "name": "apriltag_detector1",
+      "executable_name": "apriltag_detector",
+      "args": [
+          "--channel=/camera1"
+      ],
+      "user": "pi",
+      "nodes": [
+        "orin1"
+      ]
+    },
+    {
+      "name": "image_streamer",
+      "executable_name": "image_streamer",
+      "args": [
+        "--device=/dev/uvcvideo",
+        "--height=480",
+        "--width=640",
+        "--nopublish_images",
+        "--exposure=0",
+        "--framerate=30",
+        "--streaming_port=1181",
+        "--bitrate=1000000",
+        "--data_dir=/home/pi/bin/image_streamer_www"
+      ],
+      "user": "pi",
+      "nodes": [
+        "orin1"
+      ]
+    }
+  ],
+  "maps": [
+    {
+      "match": {
+        "name": "/aos*",
+        "source_node": "orin1"
+      },
+      "rename": {
+        "name": "/orin1/aos"
+      }
+    },
+    {
+      "match": {
+        "name": "/constants*",
+        "source_node": "orin1"
+      },
+      "rename": {
+        "name": "/orin1/constants"
+      }
+    },
+    {
+      "match": {
+        "name": "/camera*",
+        "source_node": "orin1"
+      },
+      "rename": {
+        "name": "/orin1/camera"
+      }
+    },
+    {
+      "match": {
+        "name": "/hardware_monitor*",
+        "source_node": "orin1"
+      },
+      "rename": {
+        "name": "/orin1/hardware_monitor"
+      }
+    }
+  ],
+  "nodes": [
+    {
+      "name": "orin1",
+      "hostname": "orin1",
+      "hostnames": [
+        "orin-971-1",
+        "orin-7971-1",
+        "orin-8971-1",
+        "orin-9971-1"
+      ],
+      "port": 9971
+    },
+    {
+      "name": "imu"
+    }
+  ]
+}
diff --git a/y2024_bot3/y2024_bot3_roborio.json b/y2024_bot3/y2024_bot3_roborio.json
new file mode 100644
index 0000000..ea5e547
--- /dev/null
+++ b/y2024_bot3/y2024_bot3_roborio.json
@@ -0,0 +1,336 @@
+{
+  "channels": [
+    {
+      "name": "/roborio/aos",
+      "type": "aos.JoystickState",
+      "source_node": "roborio",
+      "frequency": 100,
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "imu"
+      ],
+      "destination_nodes": [
+        {
+          "name": "imu",
+          "priority": 5,
+          "time_to_live": 50000000
+        }
+      ]
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "frc971.PDPValues",
+      "source_node": "roborio",
+      "frequency": 55,
+      "max_size": 368
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "aos.RobotState",
+      "source_node": "roborio",
+      "frequency": 250
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "aos.timing.Report",
+      "source_node": "roborio",
+      "frequency": 50,
+      "num_senders": 30,
+      "max_size": 8192
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "aos.logging.LogMessageFbs",
+      "source_node": "roborio",
+      "frequency": 500,
+      "max_size": 1000,
+      "num_senders": 20
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "aos.starter.Status",
+      "source_node": "roborio",
+      "frequency": 50,
+      "num_senders": 20,
+      "max_size": 2000
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "aos.starter.StarterRpc",
+      "source_node": "roborio",
+      "frequency": 10,
+      "max_size": 400,
+      "num_senders": 2
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "aos.message_bridge.ServerStatistics",
+      "source_node": "roborio",
+      "max_size": 2048,
+      "frequency": 10,
+      "num_senders": 2
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "aos.message_bridge.ClientStatistics",
+      "source_node": "roborio",
+      "frequency": 20,
+      "max_size": 2000,
+      "num_senders": 2
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "aos.logging.DynamicLogCommand",
+      "source_node": "roborio",
+      "frequency": 10,
+      "num_senders": 2
+    },
+    {
+      "name": "/roborio/aos/remote_timestamps/imu/roborio/aos/aos-message_bridge-Timestamp",
+      "type": "aos.message_bridge.RemoteMessage",
+      "frequency": 20,
+      "source_node": "roborio",
+      "max_size": 208
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "aos.message_bridge.Timestamp",
+      "source_node": "roborio",
+      "frequency": 15,
+      "num_senders": 2,
+      "max_size": 512,
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "imu"
+      ],
+      "destination_nodes": [
+        {
+          "name": "imu",
+          "priority": 1,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "roborio"
+          ],
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/superstructure",
+      "type": "y2024_bot3.control_loops.superstructure.Goal",
+      "source_node": "roborio",
+      "frequency": 250,
+      "max_size": 512
+    },
+    {
+      "name": "/superstructure",
+      "type": "y2024_bot3.control_loops.superstructure.Status",
+      "source_node": "roborio",
+      "frequency": 400,
+      "max_size": 2048,
+      "num_senders": 2
+    },
+    {
+      "name": "/superstructure",
+      "type": "y2024_bot3.control_loops.superstructure.Output",
+      "source_node": "roborio",
+      "frequency": 250,
+      "num_senders": 2,
+      "max_size": 224
+    },
+    {
+      "name": "/superstructure",
+      "type": "y2024_bot3.control_loops.superstructure.Position",
+      "source_node": "roborio",
+      "frequency": 250,
+      "num_senders": 2,
+      "max_size": 448
+    },
+    {
+      "name": "/superstructure/canivore",
+      "type": "y2024_bot3.control_loops.superstructure.CANPosition",
+      "source_node": "roborio",
+      "frequency": 220,
+      "num_senders": 2,
+      "max_size": 1024
+    },
+    {
+      "name": "/superstructure/rio",
+      "type": "y2024_bot3.control_loops.superstructure.CANPosition",
+      "source_node": "roborio",
+      "frequency": 220,
+      "num_senders": 2,
+      "max_size": 1024
+    },
+    {
+      "name": "/can",
+      "type": "frc971.can_logger.CanFrame",
+      "source_node": "roborio",
+      "frequency": 6000,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
+      "name": "/roborio",
+      "type": "frc971.CANConfiguration",
+      "source_node": "roborio",
+      "frequency": 2
+    },
+    {
+      "name": "/roborio/constants",
+      "type": "y2024_bot3.Constants",
+      "source_node": "roborio",
+      "frequency": 1,
+      "num_senders": 2,
+      "max_size": 65536
+    }
+  ],
+  "applications": [
+    {
+      "name": "trajectory_generator",
+      "executable_name": "trajectory_generator",
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "superstructure",
+      "executable_name": "superstructure",
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "roborio_irq_affinity",
+      "executable_name": "irq_affinity",
+      "args": [
+        "--irq_config=/home/admin/bin/roborio_irq_config.json"
+      ],
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "joystick_reader",
+      "executable_name": "joystick_reader",
+      "args": [
+        "--nodie_on_malloc"
+      ],
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "wpilib_interface",
+      "executable_name": "wpilib_interface",
+      "args": [
+        "--nodie_on_malloc"
+      ],
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "roborio_web_proxy",
+      "executable_name": "web_proxy_main",
+      "args": [
+        "--min_ice_port=5800",
+        "--max_ice_port=5810"
+      ],
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "roborio_message_bridge_client",
+      "executable_name": "message_bridge_client",
+      "args": [
+        "--rt_priority=16",
+        "--sinit_max_init_timeout=5000",
+        "--rmem=2097152"
+      ],
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "roborio_message_bridge_server",
+      "executable_name": "message_bridge_server",
+      "args": [
+        "--rt_priority=16",
+        "--force_wmem_max=131072"
+      ],
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "logger",
+      "executable_name": "logger_main",
+      "args": [
+        "--snappy_compress",
+        "--logging_folder=/home/admin/logs/",
+        "--rotate_every", "30.0"
+      ],
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "constants_sender_roborio",
+      "executable_name": "constants_sender",
+      "autorestart": false,
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "roborio_can_logger",
+      "executable_name": "can_logger",
+      "autostart": false,
+      "args": [
+        "--poll"
+      ],
+      "nodes": [
+        "roborio"
+      ]
+    }
+  ],
+  "maps": [
+    {
+      "match": {
+        "name": "/constants*",
+        "source_node": "roborio"
+      },
+      "rename": {
+        "name": "/roborio/constants"
+      }
+    },
+    {
+      "match": {
+        "name": "/aos*",
+        "source_node": "roborio"
+      },
+      "rename": {
+        "name": "/roborio/aos"
+      }
+    }
+  ],
+  "nodes": [
+    {
+      "name": "roborio",
+      "hostname": "roborio",
+      "hostnames": [
+        "roboRIO-971-FRC",
+        "roboRIO-6971-FRC",
+        "roboRIO-7971-FRC",
+        "roboRIO-8971-FRC",
+        "roboRIO-9971-FRC"
+      ],
+      "port": 9971
+    },
+    {
+      "name": "imu"
+    }
+  ]
+}