Add code for a practice defense bot

We want to use the 2nd robot drivetrain as a defense bot to use in drive
practice, this commit adds the folder for that robot.

Signed-off-by: Maxwell Henderson <mxwhenderson@gmail.com>
Change-Id: I8d379c8793dffe3248f1ecef83fe18040c7e0e77
diff --git a/y2024_defense/BUILD b/y2024_defense/BUILD
new file mode 100644
index 0000000..12eeec3
--- /dev/null
+++ b/y2024_defense/BUILD
@@ -0,0 +1,238 @@
+load("//frc971:downloader.bzl", "robot_downloader")
+load("//aos:config.bzl", "aos_config")
+load("//aos/util:config_validator_macro.bzl", "config_validator_test")
+
+config_validator_test(
+    name = "config_validator_test",
+    config = "//y2024_defense:aos_config",
+)
+
+robot_downloader(
+    binaries = [
+        "//aos/network:web_proxy_main",
+        "//aos/events/logging:log_cat",
+        "//aos/events:aos_timing_report_streamer",
+    ],
+    data = [
+        ":aos_config",
+        "//aos/starter:roborio_irq_config.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_defense/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_defense/control_loops/drivetrain:drivetrain",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+)
+
+robot_downloader(
+    name = "pi_download",
+    binaries = [
+        "//aos/starter:irq_affinity",
+        "//aos/util:foxglove_websocket",
+        "//aos/events:aos_timing_report_streamer",
+        "//aos/network:web_proxy_main",
+        "//aos/events/logging:log_cat",
+        "//y2024_defense/rockpi:imu_main",
+        "//frc971/image_streamer:image_streamer",
+    ],
+    data = [
+        ":aos_config",
+        "//frc971/rockpi:rockpi_config.json",
+        "//y2024_defense/www:www_files",
+        "@game_pieces_edgetpu_model//file",
+    ],
+    dirs = [
+        "//frc971/image_streamer/www:www_files",
+    ],
+    start_binaries = [
+        "//aos/network:message_bridge_client",
+        "//aos/network:message_bridge_server",
+        "//aos/network:web_proxy_main",
+        "//aos/starter:irq_affinity",
+        "//aos/events/logging:logger_main",
+    ],
+    target_compatible_with = ["//tools/platforms/hardware:raspberry_pi"],
+    target_type = "pi",
+)
+
+aos_config(
+    name = "aos_config",
+    src = "y2024_defense.json",
+    flatbuffers = [
+        "//aos/network:message_bridge_client_fbs",
+        "//aos/network:message_bridge_server_fbs",
+        "//aos/network:timestamp_fbs",
+        "//frc971/input:robot_state_fbs",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+    deps = [
+        ":config_imu",
+        ":config_roborio",
+    ],
+)
+
+aos_config(
+    name = "config_imu",
+    src = "y2024_defense_imu.json",
+    flatbuffers = [
+        "//aos/network:message_bridge_client_fbs",
+        "//aos/network:message_bridge_server_fbs",
+        "//aos/network:timestamp_fbs",
+        "//aos/network:remote_message_fbs",
+        "//frc971/control_loops/drivetrain/localization:localizer_output_fbs",
+    ],
+    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_defense_roborio.json",
+    flatbuffers = [
+        "//frc971:can_configuration_fbs",
+        "//aos/network:remote_message_fbs",
+        "//aos/network:message_bridge_client_fbs",
+        "//aos/network:message_bridge_server_fbs",
+        "//aos/network:timestamp_fbs",
+        "//frc971/control_loops/drivetrain:drivetrain_can_position_fbs",
+        "//frc971/can_logger:can_logging_fbs",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    deps = [
+        "//aos/events:aos_config",
+        "//frc971/autonomous:aos_config",
+        "//frc971/control_loops/drivetrain:aos_config",
+        "//frc971/input:aos_config",
+        "//frc971/wpilib: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/shooter_interpolation:interpolation",
+        "//frc971/zeroing:absolute_encoder",
+        "//frc971/zeroing:pot_and_absolute_encoder",
+        "//y2024_defense/control_loops/drivetrain:polydrivetrain_plants",
+        "@com_github_google_glog//:glog",
+        "@com_google_absl//absl/base",
+    ],
+)
+
+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/autonomous:auto_mode_fbs",
+        "//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:drivetrain_writer",
+        "//frc971/wpilib:encoder_and_potentiometer",
+        "//frc971/wpilib:falcon",
+        "//frc971/wpilib:interrupt_edge_counting",
+        "//frc971/wpilib:joystick_sender",
+        "//frc971/wpilib:logging_fbs",
+        "//frc971/wpilib:loop_output_handler",
+        "//frc971/wpilib:pdp_fetcher",
+        "//frc971/wpilib:sensor_reader",
+        "//frc971/wpilib:wpilib_interface",
+        "//frc971/wpilib:wpilib_robot_base",
+        "//third_party:phoenix",
+        "//third_party:phoenix6",
+        "//third_party:wpilib",
+    ],
+)
+
+cc_binary(
+    name = "joystick_reader",
+    srcs = [
+        ":joystick_reader.cc",
+    ],
+    deps = [
+        ":constants",
+        "//aos:init",
+        "//aos/actions:action_lib",
+        "//aos/logging",
+        "//frc971/autonomous:auto_fbs",
+        "//frc971/autonomous:base_autonomous_actor",
+        "//frc971/control_loops:profiled_subsystem_fbs",
+        "//frc971/input:action_joystick_input",
+        "//frc971/input:drivetrain_input",
+        "//frc971/input:joystick_input",
+        "//frc971/input:redundant_joystick_data",
+        "//y2024_defense/control_loops/drivetrain:drivetrain_base",
+    ],
+)
+
+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",
+        "//y2024_defense/www:field_main_bundle.min.js",
+        "//y2024_defense/www:files",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+)
diff --git a/y2024_defense/__init__.py b/y2024_defense/__init__.py
new file mode 100644
index 0000000..e69de29
--- /dev/null
+++ b/y2024_defense/__init__.py
diff --git a/y2024_defense/constants.cc b/y2024_defense/constants.cc
new file mode 100644
index 0000000..fa7a14c
--- /dev/null
+++ b/y2024_defense/constants.cc
@@ -0,0 +1,30 @@
+#include "y2024_defense/constants.h"
+
+#include <cinttypes>
+#include <map>
+
+#if __has_feature(address_sanitizer)
+#include "sanitizer/lsan_interface.h"
+#endif
+
+#include "absl/base/call_once.h"
+#include "glog/logging.h"
+
+#include "aos/mutex/mutex.h"
+#include "aos/network/team_number.h"
+
+namespace y2024_defense {
+namespace constants {
+
+Values MakeValues(uint16_t team) {
+  LOG(INFO) << "creating a Constants for team: " << team;
+
+  Values r;
+
+  return r;
+}
+
+Values MakeValues() { return MakeValues(aos::network::GetTeamNumber()); }
+
+}  // namespace constants
+}  // namespace y2024_defense
diff --git a/y2024_defense/constants.h b/y2024_defense/constants.h
new file mode 100644
index 0000000..7e359f4
--- /dev/null
+++ b/y2024_defense/constants.h
@@ -0,0 +1,66 @@
+#ifndef Y2023_CONSTANTS_H_
+#define Y2023_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_defense/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+
+namespace y2024_defense {
+namespace constants {
+
+constexpr uint16_t kTeamNumber = 9972;
+
+struct Values {
+  static const int kZeroingSampleSize = 200;
+
+  static const int kDrivetrainWriterPriority = 35;
+  static const int kDrivetrainTxPriority = 36;
+  static const int kDrivetrainRxPriority = 36;
+
+  static constexpr double kDrivetrainCyclesPerRevolution() { return 512.0; }
+  static constexpr double kDrivetrainEncoderCountsPerRevolution() {
+    return kDrivetrainCyclesPerRevolution() * 4;
+  }
+  static constexpr double kDrivetrainEncoderRatio() { return 1.0; }
+  static constexpr double kMaxDrivetrainEncoderPulsesPerSecond() {
+    return control_loops::drivetrain::kFreeSpeed / (2.0 * M_PI) *
+           control_loops::drivetrain::kHighOutputRatio /
+           constants::Values::kDrivetrainEncoderRatio() *
+           kDrivetrainEncoderCountsPerRevolution();
+  }
+
+  static constexpr double kDrivetrainSupplyCurrentLimit() { return 35.0; }
+  static constexpr double kDrivetrainStatorCurrentLimit() { return 60.0; }
+
+  static double DrivetrainEncoderToMeters(int32_t in) {
+    return ((static_cast<double>(in) /
+             kDrivetrainEncoderCountsPerRevolution()) *
+            (2.0 * M_PI)) *
+           kDrivetrainEncoderRatio() * control_loops::drivetrain::kWheelRadius;
+  }
+
+  static double DrivetrainCANEncoderToMeters(double rotations) {
+    return (rotations * (2.0 * M_PI)) *
+           control_loops::drivetrain::kHighOutputRatio;
+  }
+};
+
+// 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.
+Values MakeValues(uint16_t team);
+
+// Calls MakeValues with aos::network::GetTeamNumber()
+Values MakeValues();
+
+}  // namespace constants
+}  // namespace y2024_defense
+
+#endif  // Y2023_CONSTANTS_H_
diff --git a/y2024_defense/control_loops/BUILD b/y2024_defense/control_loops/BUILD
new file mode 100644
index 0000000..8dff3b6
--- /dev/null
+++ b/y2024_defense/control_loops/BUILD
@@ -0,0 +1,7 @@
+py_library(
+    name = "python_init",
+    srcs = ["__init__.py"],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+    deps = ["//y2024_defense:python_init"],
+)
diff --git a/y2024_defense/control_loops/__init__.py b/y2024_defense/control_loops/__init__.py
new file mode 100644
index 0000000..e69de29
--- /dev/null
+++ b/y2024_defense/control_loops/__init__.py
diff --git a/y2024_defense/control_loops/drivetrain/BUILD b/y2024_defense/control_loops/drivetrain/BUILD
new file mode 100644
index 0000000..664f9a1
--- /dev/null
+++ b/y2024_defense/control_loops/drivetrain/BUILD
@@ -0,0 +1,99 @@
+load("//aos:config.bzl", "aos_config")
+
+genrule(
+    name = "genrule_drivetrain",
+    outs = [
+        "drivetrain_dog_motor_plant.h",
+        "drivetrain_dog_motor_plant.cc",
+        "kalman_drivetrain_motor_plant.h",
+        "kalman_drivetrain_motor_plant.cc",
+    ],
+    cmd = "$(location //y2024_defense/control_loops/python:drivetrain) $(OUTS)",
+    target_compatible_with = ["@platforms//os:linux"],
+    tools = [
+        "//y2024_defense/control_loops/python:drivetrain",
+    ],
+)
+
+genrule(
+    name = "genrule_polydrivetrain",
+    outs = [
+        "polydrivetrain_dog_motor_plant.h",
+        "polydrivetrain_dog_motor_plant.cc",
+        "polydrivetrain_cim_plant.h",
+        "polydrivetrain_cim_plant.cc",
+        "hybrid_velocity_drivetrain.h",
+        "hybrid_velocity_drivetrain.cc",
+    ],
+    cmd = "$(location //y2024_defense/control_loops/python:polydrivetrain) $(OUTS)",
+    target_compatible_with = ["@platforms//os:linux"],
+    tools = [
+        "//y2024_defense/control_loops/python:polydrivetrain",
+    ],
+)
+
+cc_library(
+    name = "polydrivetrain_plants",
+    srcs = [
+        "drivetrain_dog_motor_plant.cc",
+        "hybrid_velocity_drivetrain.cc",
+        "kalman_drivetrain_motor_plant.cc",
+        "polydrivetrain_dog_motor_plant.cc",
+    ],
+    hdrs = [
+        "drivetrain_dog_motor_plant.h",
+        "hybrid_velocity_drivetrain.h",
+        "kalman_drivetrain_motor_plant.h",
+        "polydrivetrain_dog_motor_plant.h",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+    deps = [
+        "//frc971/control_loops:hybrid_state_feedback_loop",
+        "//frc971/control_loops:state_feedback_loop",
+    ],
+)
+
+cc_library(
+    name = "drivetrain_base",
+    srcs = [
+        "drivetrain_base.cc",
+    ],
+    hdrs = [
+        "drivetrain_base.h",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+    deps = [
+        ":polydrivetrain_plants",
+        "//frc971:shifter_hall_effect",
+        "//frc971/control_loops/drivetrain:drivetrain_config",
+    ],
+)
+
+cc_binary(
+    name = "drivetrain",
+    srcs = [
+        "drivetrain_main.cc",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+    deps = [
+        ":drivetrain_base",
+        "//aos:init",
+        "//aos/events:shm_event_loop",
+        "//frc971/control_loops/drivetrain:drivetrain_lib",
+        "//frc971/control_loops/drivetrain/localization:puppet_localizer",
+    ],
+)
+
+aos_config(
+    name = "simulation_config",
+    src = "drivetrain_simulation_config.json",
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+    deps = [
+        "//frc971/control_loops/drivetrain:simulation_channels",
+        "//y2024_defense:aos_config",
+    ],
+)
diff --git a/y2024_defense/control_loops/drivetrain/drivetrain_base.cc b/y2024_defense/control_loops/drivetrain/drivetrain_base.cc
new file mode 100644
index 0000000..5d14833
--- /dev/null
+++ b/y2024_defense/control_loops/drivetrain/drivetrain_base.cc
@@ -0,0 +1,90 @@
+#include "y2024_defense/control_loops/drivetrain/drivetrain_base.h"
+
+#include <chrono>
+
+#include "frc971/control_loops/drivetrain/drivetrain_config.h"
+#include "frc971/control_loops/state_feedback_loop.h"
+#include "y2024_defense/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+#include "y2024_defense/control_loops/drivetrain/hybrid_velocity_drivetrain.h"
+#include "y2024_defense/control_loops/drivetrain/kalman_drivetrain_motor_plant.h"
+#include "y2024_defense/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
+
+using ::frc971::control_loops::drivetrain::DownEstimatorConfig;
+using ::frc971::control_loops::drivetrain::DrivetrainConfig;
+using ::frc971::control_loops::drivetrain::LineFollowConfig;
+
+namespace chrono = ::std::chrono;
+
+namespace y2024_defense {
+namespace control_loops {
+namespace drivetrain {
+
+using ::frc971::constants::ShifterHallEffect;
+
+const ShifterHallEffect kThreeStateDriveShifter{0.0, 0.0, 0.25, 0.75};
+
+const DrivetrainConfig<double> &GetDrivetrainConfig() {
+  // Yaw of the IMU relative to the robot frame.
+  static constexpr double kImuYaw = 0.0;
+  static DrivetrainConfig<double> kDrivetrainConfig{
+      ::frc971::control_loops::drivetrain::ShifterType::SIMPLE_SHIFTER,
+      ::frc971::control_loops::drivetrain::LoopType::CLOSED_LOOP,
+      ::frc971::control_loops::drivetrain::GyroType::SPARTAN_GYRO,
+      ::frc971::control_loops::drivetrain::IMUType::IMU_FLIPPED_X,
+
+      drivetrain::MakeDrivetrainLoop,
+      drivetrain::MakeVelocityDrivetrainLoop,
+      drivetrain::MakeKFDrivetrainLoop,
+      drivetrain::MakeHybridVelocityDrivetrainLoop,
+
+      chrono::duration_cast<chrono::nanoseconds>(
+          chrono::duration<double>(drivetrain::kDt)),
+      drivetrain::kRobotRadius,
+      drivetrain::kWheelRadius,
+      drivetrain::kV,
+
+      drivetrain::kHighGearRatio,
+      drivetrain::kLowGearRatio,
+      drivetrain::kJ,
+      drivetrain::kMass,
+      kThreeStateDriveShifter,
+      kThreeStateDriveShifter,
+      true /* default_high_gear */,
+      0 /* down_offset if using constants use
+     constants::GetValues().down_error */
+      ,
+      0.7 /* wheel_non_linearity */,
+      1.2 /* quickturn_wheel_multiplier */,
+      1.2 /* wheel_multiplier */,
+      false /*pistol_grip_shift_enables_line_follow*/,
+      (Eigen::Matrix<double, 3, 3>() << std::cos(kImuYaw), -std::sin(kImuYaw),
+       0.0, std::sin(kImuYaw), std::cos(kImuYaw), 0.0, 0.0, 0.0, 1.0)
+          .finished(),
+      false /*is_simulated*/,
+      DownEstimatorConfig{.gravity_threshold = 0.015,
+                          .do_accel_corrections = 1000},
+      LineFollowConfig{
+          .Q = Eigen::Matrix3d((::Eigen::DiagonalMatrix<double, 3>().diagonal()
+                                    << 1.0 / ::std::pow(0.1, 2),
+                                1.0 / ::std::pow(1.0, 2),
+                                1.0 / ::std::pow(1.0, 2))
+                                   .finished()
+                                   .asDiagonal()),
+          .R = Eigen::Matrix2d((::Eigen::DiagonalMatrix<double, 2>().diagonal()
+                                    << 10.0 / ::std::pow(12.0, 2),
+                                10.0 / ::std::pow(12.0, 2))
+                                   .finished()
+                                   .asDiagonal()),
+          .max_controllable_offset = 0.5},
+      frc971::control_loops::drivetrain::PistolTopButtonUse::kNone,
+      frc971::control_loops::drivetrain::PistolSecondButtonUse::kTurn1,
+      frc971::control_loops::drivetrain::PistolBottomButtonUse::
+          kControlLoopDriving,
+  };
+
+  return kDrivetrainConfig;
+};
+
+}  // namespace drivetrain
+}  // namespace control_loops
+}  // namespace y2024_defense
diff --git a/y2024_defense/control_loops/drivetrain/drivetrain_base.h b/y2024_defense/control_loops/drivetrain/drivetrain_base.h
new file mode 100644
index 0000000..622de4f
--- /dev/null
+++ b/y2024_defense/control_loops/drivetrain/drivetrain_base.h
@@ -0,0 +1,17 @@
+#ifndef Y2023_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
+#define Y2023_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
+
+#include "frc971/control_loops/drivetrain/drivetrain_config.h"
+
+namespace y2024_defense {
+namespace control_loops {
+namespace drivetrain {
+
+const ::frc971::control_loops::drivetrain::DrivetrainConfig<double> &
+GetDrivetrainConfig();
+
+}  // namespace drivetrain
+}  // namespace control_loops
+}  // namespace y2024_defense
+
+#endif  // Y2023_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
diff --git a/y2024_defense/control_loops/drivetrain/drivetrain_main.cc b/y2024_defense/control_loops/drivetrain/drivetrain_main.cc
new file mode 100644
index 0000000..968e312
--- /dev/null
+++ b/y2024_defense/control_loops/drivetrain/drivetrain_main.cc
@@ -0,0 +1,30 @@
+#include <memory>
+
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "frc971/control_loops/drivetrain/drivetrain.h"
+#include "frc971/control_loops/drivetrain/localization/puppet_localizer.h"
+#include "y2024_defense/control_loops/drivetrain/drivetrain_base.h"
+
+using ::frc971::control_loops::drivetrain::DrivetrainLoop;
+
+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());
+  std::unique_ptr<::frc971::control_loops::drivetrain::PuppetLocalizer>
+      localizer = std::make_unique<
+          ::frc971::control_loops::drivetrain::PuppetLocalizer>(
+          &event_loop,
+          ::y2024_defense::control_loops::drivetrain::GetDrivetrainConfig());
+  std::unique_ptr<DrivetrainLoop> drivetrain = std::make_unique<DrivetrainLoop>(
+      y2024_defense::control_loops::drivetrain::GetDrivetrainConfig(),
+      &event_loop, localizer.get());
+
+  event_loop.Run();
+
+  return 0;
+}
diff --git a/y2024_defense/control_loops/drivetrain/drivetrain_simulation_config.json b/y2024_defense/control_loops/drivetrain/drivetrain_simulation_config.json
new file mode 100644
index 0000000..8251739
--- /dev/null
+++ b/y2024_defense/control_loops/drivetrain/drivetrain_simulation_config.json
@@ -0,0 +1,6 @@
+{
+  "imports": [
+    "../../y2024_defense.json",
+    "../../../frc971/control_loops/drivetrain/drivetrain_simulation_channels.json"
+  ]
+}
diff --git a/y2024_defense/control_loops/python/BUILD b/y2024_defense/control_loops/python/BUILD
new file mode 100644
index 0000000..eec5e9f
--- /dev/null
+++ b/y2024_defense/control_loops/python/BUILD
@@ -0,0 +1,57 @@
+package(default_visibility = ["//y2024_defense:__subpackages__"])
+
+py_binary(
+    name = "drivetrain",
+    srcs = [
+        "drivetrain.py",
+    ],
+    legacy_create_init = False,
+    target_compatible_with = ["@platforms//cpu:x86_64"],
+    deps = [
+        ":python_init",
+        "//frc971/control_loops/python:drivetrain",
+        "@pip//glog",
+        "@pip//python_gflags",
+    ],
+)
+
+py_binary(
+    name = "polydrivetrain",
+    srcs = [
+        "drivetrain.py",
+        "polydrivetrain.py",
+    ],
+    legacy_create_init = False,
+    target_compatible_with = ["@platforms//cpu:x86_64"],
+    deps = [
+        ":python_init",
+        "//frc971/control_loops/python:polydrivetrain",
+        "@pip//glog",
+        "@pip//python_gflags",
+    ],
+)
+
+py_library(
+    name = "polydrivetrain_lib",
+    srcs = [
+        "drivetrain.py",
+        "polydrivetrain.py",
+    ],
+    target_compatible_with = ["@platforms//cpu:x86_64"],
+    visibility = ["//visibility:public"],
+    deps = [
+        "//frc971/control_loops/python:controls",
+        "//frc971/control_loops/python:drivetrain",
+        "//frc971/control_loops/python:polydrivetrain",
+        "@pip//glog",
+        "@pip//python_gflags",
+    ],
+)
+
+py_library(
+    name = "python_init",
+    srcs = ["__init__.py"],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+    deps = ["//y2024_defense/control_loops:python_init"],
+)
diff --git a/y2024_defense/control_loops/python/__init__.py b/y2024_defense/control_loops/python/__init__.py
new file mode 100644
index 0000000..e69de29
--- /dev/null
+++ b/y2024_defense/control_loops/python/__init__.py
diff --git a/y2024_defense/control_loops/python/drivetrain.py b/y2024_defense/control_loops/python/drivetrain.py
new file mode 100644
index 0000000..438eb24
--- /dev/null
+++ b/y2024_defense/control_loops/python/drivetrain.py
@@ -0,0 +1,48 @@
+#!/usr/bin/python3
+
+from __future__ import print_function
+from frc971.control_loops.python import drivetrain
+from frc971.control_loops.python import control_loop
+import sys
+
+import gflags
+import glog
+
+FLAGS = gflags.FLAGS
+
+gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+
+kDrivetrain = drivetrain.DrivetrainParams(
+    J=6.5,
+    mass=68.0,
+    # TODO(austin): Measure radius a bit better.
+    robot_radius=0.39,
+    wheel_radius=2.5 * 0.0254,
+    motor_type=control_loop.Falcon(),
+    num_motors=3,
+    G=(14.0 / 52.0) * (26.0 / 58.0),
+    q_pos=0.24,
+    q_vel=2.5,
+    efficiency=0.92,
+    has_imu=False,
+    force=True,
+    kf_q_voltage=1.0,
+    controller_poles=[0.82, 0.82])
+
+
+def main(argv):
+    argv = FLAGS(argv)
+    glog.init()
+
+    if FLAGS.plot:
+        drivetrain.PlotDrivetrainMotions(kDrivetrain)
+    elif len(argv) != 5:
+        print("Expected .h file name and .cc file name")
+    else:
+        # Write the generated constants out to a file.
+        drivetrain.WriteDrivetrain(argv[1:3], argv[3:5], 'y2024_defense',
+                                   kDrivetrain)
+
+
+if __name__ == '__main__':
+    sys.exit(main(sys.argv))
diff --git a/y2024_defense/control_loops/python/polydrivetrain.py b/y2024_defense/control_loops/python/polydrivetrain.py
new file mode 100644
index 0000000..301c7b5
--- /dev/null
+++ b/y2024_defense/control_loops/python/polydrivetrain.py
@@ -0,0 +1,34 @@
+#!/usr/bin/python3
+
+import sys
+from y2024_defense.control_loops.python import drivetrain
+from frc971.control_loops.python import polydrivetrain
+
+import gflags
+import glog
+
+__author__ = 'Austin Schuh (austin.linux@gmail.com)'
+
+FLAGS = gflags.FLAGS
+
+try:
+    gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+except gflags.DuplicateFlagError:
+    pass
+
+
+def main(argv):
+    if FLAGS.plot:
+        polydrivetrain.PlotPolyDrivetrainMotions(drivetrain.kDrivetrain)
+    elif len(argv) != 7:
+        glog.fatal('Expected .h file name and .cc file name')
+    else:
+        polydrivetrain.WritePolyDrivetrain(argv[1:3], argv[3:5], argv[5:7],
+                                           'y2024_defense',
+                                           drivetrain.kDrivetrain)
+
+
+if __name__ == '__main__':
+    argv = FLAGS(sys.argv)
+    glog.init()
+    sys.exit(main(argv))
diff --git a/y2024_defense/joystick_reader.cc b/y2024_defense/joystick_reader.cc
new file mode 100644
index 0000000..8c3115b
--- /dev/null
+++ b/y2024_defense/joystick_reader.cc
@@ -0,0 +1,65 @@
+#include <unistd.h>
+
+#include <cmath>
+#include <cstdio>
+#include <cstring>
+
+#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/control_loops/drivetrain/localizer_generated.h"
+#include "frc971/control_loops/profiled_subsystem_generated.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_defense/constants.h"
+#include "y2024_defense/control_loops/drivetrain/drivetrain_base.h"
+
+using Side = frc971::control_loops::drivetrain::RobotSide;
+
+namespace y2024_defense {
+namespace input {
+namespace joysticks {
+
+class Reader : public ::frc971::input::ActionJoystickInput {
+ public:
+  Reader(::aos::EventLoop *event_loop)
+      : ::frc971::input::ActionJoystickInput(
+            event_loop,
+            ::y2024_defense::control_loops::drivetrain::GetDrivetrainConfig(),
+            ::frc971::input::DrivetrainInputReader::InputType::kPistol,
+            {.use_redundant_joysticks = true}) {}
+
+  void AutoEnded() override { AOS_LOG(INFO, "Auto ended.\n"); }
+
+  bool has_scored_ = false;
+
+  void HandleTeleop(
+      const ::frc971::input::driver_station::Data &data) override {
+    (void)data;
+  }
+};
+
+}  // namespace joysticks
+}  // namespace input
+}  // namespace y2024_defense
+
+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());
+  ::y2024_defense::input::joysticks::Reader reader(&event_loop);
+
+  event_loop.Run();
+
+  return 0;
+}
diff --git a/y2024_defense/log_web_proxy.sh b/y2024_defense/log_web_proxy.sh
new file mode 100755
index 0000000..714d491
--- /dev/null
+++ b/y2024_defense/log_web_proxy.sh
@@ -0,0 +1 @@
+./aos/network/log_web_proxy_main --data_dir=y2024_defense/www $@
diff --git a/y2024_defense/rockpi/BUILD b/y2024_defense/rockpi/BUILD
new file mode 100644
index 0000000..756a694
--- /dev/null
+++ b/y2024_defense/rockpi/BUILD
@@ -0,0 +1,12 @@
+cc_binary(
+    name = "imu_main",
+    srcs = ["imu_main.cc"],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+    deps = [
+        "//aos:init",
+        "//aos/events:shm_event_loop",
+        "//frc971/imu_reader:imu",
+        "//y2024_defense:constants",
+    ],
+)
diff --git a/y2024_defense/rockpi/imu_main.cc b/y2024_defense/rockpi/imu_main.cc
new file mode 100644
index 0000000..8ab51fe
--- /dev/null
+++ b/y2024_defense/rockpi/imu_main.cc
@@ -0,0 +1,26 @@
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "aos/realtime.h"
+#include "frc971/imu_reader/imu.h"
+#include "y2024_defense/constants.h"
+
+DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
+
+int main(int argc, char *argv[]) {
+  aos::InitGoogle(&argc, &argv);
+
+  aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+      aos::configuration::ReadConfig(FLAGS_config);
+
+  aos::ShmEventLoop event_loop(&config.message());
+  frc971::imu::Imu imu(
+      &event_loop,
+      y2024_defense::constants::Values::DrivetrainEncoderToMeters(1));
+
+  event_loop.SetRuntimeAffinity(aos::MakeCpusetFromCpus({0}));
+  event_loop.SetRuntimeRealtimePriority(55);
+
+  event_loop.Run();
+
+  return 0;
+}
diff --git a/y2024_defense/wpilib_interface.cc b/y2024_defense/wpilib_interface.cc
new file mode 100644
index 0000000..7cecb21
--- /dev/null
+++ b/y2024_defense/wpilib_interface.cc
@@ -0,0 +1,381 @@
+#include <unistd.h>
+
+#include <array>
+#include <chrono>
+#include <cinttypes>
+#include <cmath>
+#include <cstdio>
+#include <cstring>
+#include <functional>
+#include <memory>
+#include <mutex>
+#include <thread>
+
+#include "ctre/phoenix/CANifier.h"
+
+#include "frc971/wpilib/ahal/AnalogInput.h"
+#include "frc971/wpilib/ahal/Counter.h"
+#include "frc971/wpilib/ahal/DigitalGlitchFilter.h"
+#include "frc971/wpilib/ahal/DriverStation.h"
+#include "frc971/wpilib/ahal/Encoder.h"
+#include "frc971/wpilib/ahal/Servo.h"
+#include "frc971/wpilib/ahal/TalonFX.h"
+#include "frc971/wpilib/ahal/VictorSP.h"
+#undef ERROR
+
+#include "ctre/phoenix/cci/Diagnostics_CCI.h"
+#include "ctre/phoenix6/TalonFX.hpp"
+
+#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/autonomous/auto_mode_generated.h"
+#include "frc971/can_configuration_generated.h"
+#include "frc971/control_loops/drivetrain/drivetrain_can_position_generated.h"
+#include "frc971/control_loops/drivetrain/drivetrain_position_generated.h"
+#include "frc971/input/robot_state_generated.h"
+#include "frc971/queues/gyro_generated.h"
+#include "frc971/wpilib/ADIS16448.h"
+#include "frc971/wpilib/buffered_pcm.h"
+#include "frc971/wpilib/buffered_solenoid.h"
+#include "frc971/wpilib/can_drivetrain_writer.h"
+#include "frc971/wpilib/can_sensor_reader.h"
+#include "frc971/wpilib/dma.h"
+#include "frc971/wpilib/drivetrain_writer.h"
+#include "frc971/wpilib/encoder_and_potentiometer.h"
+#include "frc971/wpilib/falcon.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/wpilib_robot_base.h"
+#include "y2024_defense/constants.h"
+
+DEFINE_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 ::y2024_defense::constants::Values;
+
+using frc971::control_loops::drivetrain::CANPosition;
+using frc971::wpilib::Falcon;
+
+using std::make_unique;
+
+namespace y2024_defense {
+namespace wpilib {
+namespace {
+
+constexpr double kMaxBringupPower = 12.0;
+
+double drivetrain_velocity_translate(double in) {
+  return (((1.0 / in) / Values::kDrivetrainCyclesPerRevolution()) *
+          (2.0 * M_PI)) *
+         Values::kDrivetrainEncoderRatio() *
+         control_loops::drivetrain::kWheelRadius;
+}
+
+constexpr double kMaxFastEncoderPulsesPerSecond = std::max({
+    Values::kMaxDrivetrainEncoderPulsesPerSecond(),
+});
+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,
+               std::shared_ptr<const Values> values)
+      : ::frc971::wpilib::SensorReader(event_loop),
+        values_(std::move(values)),
+        auto_mode_sender_(
+            event_loop->MakeSender<::frc971::autonomous::AutonomousMode>(
+                "/autonomous")),
+        drivetrain_position_sender_(
+            event_loop
+                ->MakeSender<::frc971::control_loops::drivetrain::Position>(
+                    "/drivetrain")),
+        gyro_sender_(event_loop->MakeSender<::frc971::sensors::GyroReading>(
+            "/drivetrain")) {
+    // Set to filter out anything shorter than 1/4 of the minimum pulse width
+    // we should ever see.
+    UpdateFastEncoderFilterHz(kMaxFastEncoderPulsesPerSecond);
+    event_loop->SetRuntimeAffinity(aos::MakeCpusetFromCpus({0}));
+  }
+
+  void Start() override { AddToDMA(&imu_yaw_rate_reader_); }
+
+  // Auto mode switches.
+  void set_autonomous_mode(int i, ::std::unique_ptr<frc::DigitalInput> sensor) {
+    autonomous_modes_.at(i) = ::std::move(sensor);
+  }
+
+  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 {
+    superstructure_reading_->Set(true);
+    {
+      {
+        auto builder = drivetrain_position_sender_.MakeBuilder();
+        frc971::control_loops::drivetrain::Position::Builder
+            drivetrain_builder =
+                builder
+                    .MakeBuilder<frc971::control_loops::drivetrain::Position>();
+        drivetrain_builder.add_left_encoder(
+            constants::Values::DrivetrainEncoderToMeters(
+                drivetrain_left_encoder_->GetRaw()));
+        drivetrain_builder.add_left_speed(drivetrain_velocity_translate(
+            drivetrain_left_encoder_->GetPeriod()));
+
+        drivetrain_builder.add_right_encoder(
+            -constants::Values::DrivetrainEncoderToMeters(
+                drivetrain_right_encoder_->GetRaw()));
+        drivetrain_builder.add_right_speed(-drivetrain_velocity_translate(
+            drivetrain_right_encoder_->GetPeriod()));
+
+        builder.CheckOk(builder.Send(drivetrain_builder.Finish()));
+      }
+
+      {
+        auto builder = gyro_sender_.MakeBuilder();
+        ::frc971::sensors::GyroReading::Builder gyro_reading_builder =
+            builder.MakeBuilder<::frc971::sensors::GyroReading>();
+        // +/- 2000 deg / sec
+        constexpr double kMaxVelocity = 4000;  // degrees / second
+        constexpr double kVelocityRadiansPerSecond =
+            kMaxVelocity / 360 * (2.0 * M_PI);
+
+        // Only part of the full range is used to prevent being 100% on or off.
+        constexpr double kScaledRangeLow = 0.1;
+        constexpr double kScaledRangeHigh = 0.9;
+
+        constexpr double kPWMFrequencyHz = 200;
+        double velocity_duty_cycle =
+            imu_yaw_rate_reader_.last_width() * kPWMFrequencyHz;
+
+        constexpr double kDutyCycleScale =
+            1 / (kScaledRangeHigh - kScaledRangeLow);
+        // scale from 0.1 - 0.9 to 0 - 1
+        double rescaled_velocity_duty_cycle =
+            (velocity_duty_cycle - kScaledRangeLow) * kDutyCycleScale;
+
+        if (!std::isnan(rescaled_velocity_duty_cycle)) {
+          gyro_reading_builder.add_velocity(
+              (rescaled_velocity_duty_cycle - 0.5) * kVelocityRadiansPerSecond);
+        }
+        builder.CheckOk(builder.Send(gyro_reading_builder.Finish()));
+      }
+
+      {
+        auto builder = auto_mode_sender_.MakeBuilder();
+
+        uint32_t mode = 0;
+        for (size_t i = 0; i < autonomous_modes_.size(); ++i) {
+          if (autonomous_modes_[i] && autonomous_modes_[i]->Get()) {
+            mode |= 1 << i;
+          }
+        }
+
+        auto auto_mode_builder =
+            builder.MakeBuilder<frc971::autonomous::AutonomousMode>();
+
+        auto_mode_builder.add_mode(mode);
+
+        builder.CheckOk(builder.Send(auto_mode_builder.Finish()));
+      }
+    }
+  }
+
+  std::shared_ptr<frc::DigitalOutput> superstructure_reading_;
+
+  void set_superstructure_reading(
+      std::shared_ptr<frc::DigitalOutput> superstructure_reading) {
+    superstructure_reading_ = superstructure_reading;
+  }
+
+ private:
+  std::shared_ptr<const Values> values_;
+
+  aos::Sender<frc971::autonomous::AutonomousMode> auto_mode_sender_;
+  aos::Sender<frc971::control_loops::drivetrain::Position>
+      drivetrain_position_sender_;
+  ::aos::Sender<::frc971::sensors::GyroReading> gyro_sender_;
+
+  std::array<std::unique_ptr<frc::DigitalInput>, 2> autonomous_modes_;
+
+  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 {
+    std::shared_ptr<const Values> values =
+        std::make_shared<const Values>(constants::MakeValues());
+
+    aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+        aos::configuration::ReadConfig("aos_config.json");
+
+    // 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, values);
+    std::shared_ptr<frc::DigitalOutput> superstructure_reading =
+        make_unique<frc::DigitalOutput>(25);
+
+    sensor_reader.set_pwm_trigger(true);
+    sensor_reader.set_drivetrain_left_encoder(make_encoder(1));
+    sensor_reader.set_drivetrain_right_encoder(make_encoder(0));
+    sensor_reader.set_superstructure_reading(superstructure_reading);
+    sensor_reader.set_yaw_rate_input(make_unique<frc::DigitalInput>(0));
+
+    AddLoop(&sensor_reader_event_loop);
+
+    // Thread 4.
+    std::vector<ctre::phoenix6::BaseStatusSignal *> signals_registry;
+
+    std::shared_ptr<Falcon> right_front = std::make_shared<Falcon>(
+        1, true, "Drivetrain Bus", &signals_registry,
+        constants::Values::kDrivetrainStatorCurrentLimit(),
+        constants::Values::kDrivetrainSupplyCurrentLimit());
+    std::shared_ptr<Falcon> right_back = std::make_shared<Falcon>(
+        2, true, "Drivetrain Bus", &signals_registry,
+        constants::Values::kDrivetrainStatorCurrentLimit(),
+        constants::Values::kDrivetrainSupplyCurrentLimit());
+    std::shared_ptr<Falcon> right_under = std::make_shared<Falcon>(
+        3, true, "Drivetrain Bus", &signals_registry,
+        constants::Values::kDrivetrainStatorCurrentLimit(),
+        constants::Values::kDrivetrainSupplyCurrentLimit());
+    std::shared_ptr<Falcon> left_front = std::make_shared<Falcon>(
+        4, false, "Drivetrain Bus", &signals_registry,
+        constants::Values::kDrivetrainStatorCurrentLimit(),
+        constants::Values::kDrivetrainSupplyCurrentLimit());
+    std::shared_ptr<Falcon> left_back = std::make_shared<Falcon>(
+        5, false, "Drivetrain Bus", &signals_registry,
+        constants::Values::kDrivetrainStatorCurrentLimit(),
+        constants::Values::kDrivetrainSupplyCurrentLimit());
+    std::shared_ptr<Falcon> left_under = std::make_shared<Falcon>(
+        6, false, "Drivetrain Bus", &signals_registry,
+        constants::Values::kDrivetrainStatorCurrentLimit(),
+        constants::Values::kDrivetrainSupplyCurrentLimit());
+
+    // Setting up CAN.
+    if (!FLAGS_ctre_diag_server) {
+      c_Phoenix_Diagnostics_SetSecondsToStart(-1);
+      c_Phoenix_Diagnostics_Dispose();
+    }
+
+    // Creating list of falcons for CANSensorReader
+    std::vector<std::shared_ptr<Falcon>> falcons;
+    for (auto falcon : {right_front, right_back, right_under, left_front,
+                        left_back, left_under}) {
+      falcons.push_back(falcon);
+    }
+
+    ctre::phoenix::platform::can::CANComm_SetRxSchedPriority(
+        constants::Values::kDrivetrainRxPriority, true, "Drivetrain Bus");
+    ctre::phoenix::platform::can::CANComm_SetTxSchedPriority(
+        constants::Values::kDrivetrainTxPriority, true, "Drivetrain Bus");
+
+    ::aos::ShmEventLoop can_sensor_reader_event_loop(&config.message());
+    can_sensor_reader_event_loop.set_name("CANSensorReader");
+
+    aos::Sender<CANPosition> can_position_sender =
+        can_sensor_reader_event_loop.MakeSender<CANPosition>("/drivetrain");
+
+    frc971::wpilib::CANSensorReader can_sensor_reader(
+        &can_sensor_reader_event_loop, std::move(signals_registry), falcons,
+        [falcons, &can_position_sender](ctre::phoenix::StatusCode status) {
+          auto builder = can_position_sender.MakeBuilder();
+          aos::SizedArray<flatbuffers::Offset<frc971::control_loops::CANFalcon>,
+                          6>
+              flatbuffer_falcons;
+
+          for (auto falcon : falcons) {
+            falcon->SerializePosition(
+                builder.fbb(), control_loops::drivetrain::kHighOutputRatio);
+            std::optional<flatbuffers::Offset<frc971::control_loops::CANFalcon>>
+                falcon_offset = falcon->TakeOffset();
+
+            CHECK(falcon_offset.has_value());
+
+            flatbuffer_falcons.push_back(falcon_offset.value());
+          }
+
+          auto falcons_list =
+              builder.fbb()
+                  ->CreateVector<
+                      flatbuffers::Offset<frc971::control_loops::CANFalcon>>(
+                      flatbuffer_falcons);
+
+          frc971::control_loops::drivetrain::CANPosition::Builder
+              can_position_builder = builder.MakeBuilder<
+                  frc971::control_loops::drivetrain::CANPosition>();
+
+          can_position_builder.add_falcons(falcons_list);
+          can_position_builder.add_timestamp(falcons.front()->GetTimestamp());
+          can_position_builder.add_status(static_cast<int>(status));
+
+          builder.CheckOk(builder.Send(can_position_builder.Finish()));
+        });
+
+    AddLoop(&can_sensor_reader_event_loop);
+
+    // Thread 5.
+    ::aos::ShmEventLoop can_drivetrain_writer_event_loop(&config.message());
+    can_drivetrain_writer_event_loop.set_name("CANDrivetrainWriter");
+
+    frc971::wpilib::CANDrivetrainWriter can_drivetrain_writer(
+        &can_drivetrain_writer_event_loop);
+
+    can_drivetrain_writer.set_falcons({right_front, right_back, right_under},
+                                      {left_front, left_back, left_under});
+
+    can_drivetrain_writer_event_loop.MakeWatcher(
+        "/roborio", [&can_drivetrain_writer](
+                        const frc971::CANConfiguration &configuration) {
+          can_drivetrain_writer.HandleCANConfiguration(configuration);
+        });
+
+    AddLoop(&can_drivetrain_writer_event_loop);
+
+    RunLoops();
+  }
+};
+
+}  // namespace wpilib
+}  // namespace y2024_defense
+
+AOS_ROBOT_CLASS(::y2024_defense::wpilib::WPILibRobot);
diff --git a/y2024_defense/www/BUILD b/y2024_defense/www/BUILD
new file mode 100644
index 0000000..7af68fe
--- /dev/null
+++ b/y2024_defense/www/BUILD
@@ -0,0 +1,63 @@
+load("//tools/build_rules:js.bzl", "rollup_bundle", "ts_project")
+load("//frc971/downloader:downloader.bzl", "aos_downloader_dir")
+
+filegroup(
+    name = "files",
+    srcs = glob([
+        "**/*.html",
+        "**/*.css",
+        "**/*.png",
+    ]) + ["2023.png"],
+    visibility = ["//visibility:public"],
+)
+
+# TODO(max): This needs to be changed once the season starts
+genrule(
+    name = "2023_field_png",
+    srcs = ["//third_party/y2023/field:pictures"],
+    outs = ["2023.png"],
+    cmd = "cp third_party/y2023/field/2023.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_status_ts_fbs",
+        "//frc971/control_loops/drivetrain/localization:localizer_output_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_defense:__subpackages__"],
+    deps = [
+        ":field_main",
+    ],
+)
+
+aos_downloader_dir(
+    name = "www_files",
+    srcs = [
+        ":field_main_bundle.min.js",
+        ":files",
+        "//frc971/analysis:plot_index_bundle.min.js",
+    ],
+    dir = "www",
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+)
diff --git a/y2024_defense/www/constants.ts b/y2024_defense/www/constants.ts
new file mode 100644
index 0000000..d6ecfaf
--- /dev/null
+++ b/y2024_defense/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 + 7.25 * IN_TO_M;
+export const FIELD_LENGTH = 54 * FT_TO_M + 5.25 * IN_TO_M;
+
diff --git a/y2024_defense/www/field.html b/y2024_defense/www/field.html
new file mode 100644
index 0000000..d086af7
--- /dev/null
+++ b/y2024_defense/www/field.html
@@ -0,0 +1,41 @@
+<html>
+  <head>
+    <script src="field_main_bundle.min.js" defer></script>
+    <link rel="stylesheet" href="styles.css">
+  </head>
+  <body>
+    <div id="field"> </div>
+    <div id="legend"> </div>
+    <div id="readouts">
+      <table>
+        <tr>
+          <th colspan="2">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>
+  <h3>Zeroing Faults:</h3>
+  <p id="zeroing_faults"> NA </p>
+  </div>
+  <div id="middle_readouts">
+    <div id="message_bridge_status">
+      <div>
+        <div>Node</div>
+        <div>Client</div>
+        <div>Server</div>
+      </div>
+    </div>
+  </div>
+  </body>
+</html>
+
diff --git a/y2024_defense/www/field_handler.ts b/y2024_defense/www/field_handler.ts
new file mode 100644
index 0000000..8010b10
--- /dev/null
+++ b/y2024_defense/www/field_handler.ts
@@ -0,0 +1,261 @@
+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 {Status as DrivetrainStatus} from '../../frc971/control_loops/drivetrain/drivetrain_status_generated'
+import {LocalizerOutput} from '../../frc971/control_loops/drivetrain/localization/localizer_output_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 = 25 * IN_TO_M;
+const ROBOT_LENGTH = 32 * IN_TO_M;
+
+const PI_COLORS = ['#ff00ff', '#ffff00', '#00ffff', '#ffa500'];
+const PIS = ['pi1', 'pi2', 'pi3', 'pi4'];
+
+export class FieldHandler {
+  private canvas = document.createElement('canvas');
+  private localizerOutput: LocalizerOutput|null = null;
+  private drivetrainStatus: DrivetrainStatus|null = null;
+
+  private x: HTMLElement = (document.getElementById('x') as HTMLElement);
+  private y: HTMLElement = (document.getElementById('y') as HTMLElement);
+  private theta: HTMLElement =
+      (document.getElementById('theta') as HTMLElement);
+  // HTML elements for rejection reasons for individual pis. 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 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();
+  
+  constructor(private readonly connection: Connection) {
+    (document.getElementById('field') as HTMLElement).appendChild(this.canvas);
+
+    this.fieldImage.src = '2023.png';
+
+    this.connection.addConfigHandler(() => {
+      // Visualization message is reliable so that we can see *all* the vision
+      // matches.
+      this.connection.addHandler(
+          '/drivetrain', 'frc971.control_loops.drivetrain.Status', (data) => {
+            this.handleDrivetrainStatus(data);
+          });
+      this.connection.addHandler(
+          '/localizer', 'frc971.controls.LocalizerOutput', (data) => {
+            this.handleLocalizerOutput(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 handleLocalizerOutput(data: Uint8Array): void {
+    const fbBuffer = new ByteBuffer(data);
+    this.localizerOutput = LocalizerOutput.getRootAsLocalizerOutput(fbBuffer);
+  }
+
+  private handleDrivetrainStatus(data: Uint8Array): void {
+    const fbBuffer = new ByteBuffer(data);
+    this.drivetrainStatus = DrivetrainStatus.getRootAsStatus(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());
+    }
+  }
+
+  setZeroing(div: HTMLElement): void {
+    div.innerHTML = 'zeroing';
+    div.classList.remove('faulted');
+    div.classList.add('zeroing');
+    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');
+  }
+
+  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();
+  }
+
+  draw(): void {
+    this.reset();
+    this.drawField();
+
+    // Draw the matches with debugging information from the localizer.
+    const now = Date.now() / 1000.0;
+
+    if (this.drivetrainStatus && this.drivetrainStatus.trajectoryLogging()) {
+      this.drawRobot(
+          this.drivetrainStatus.trajectoryLogging().x(),
+          this.drivetrainStatus.trajectoryLogging().y(),
+          this.drivetrainStatus.trajectoryLogging().theta(), '#000000FF',
+          false);
+    }
+
+    if (this.localizerOutput) {
+      if (!this.localizerOutput.zeroed()) {
+        this.setZeroing(this.x);
+        this.setZeroing(this.y);
+        this.setZeroing(this.theta);
+      } else {
+        this.setValue(this.x, this.localizerOutput.x());
+        this.setValue(this.y, this.localizerOutput.y());
+        this.setValue(this.theta, this.localizerOutput.theta());
+      }
+
+      this.drawRobot(
+          this.localizerOutput.x(), this.localizerOutput.y(),
+          this.localizerOutput.theta());
+    }
+
+
+    window.requestAnimationFrame(() => this.draw());
+  }
+
+  reset(): void {
+    const ctx = this.canvas.getContext('2d');
+    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 - 10) / FIELD_LENGTH;
+    ctx.scale(M_TO_PX, M_TO_PX);
+    ctx.lineWidth = 1 / M_TO_PX;
+  }
+}
diff --git a/y2024_defense/www/field_main.ts b/y2024_defense/www/field_main.ts
new file mode 100644
index 0000000..d71a45e
--- /dev/null
+++ b/y2024_defense/www/field_main.ts
@@ -0,0 +1,12 @@
+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_defense/www/index.html b/y2024_defense/www/index.html
new file mode 100644
index 0000000..e4e185e
--- /dev/null
+++ b/y2024_defense/www/index.html
@@ -0,0 +1,6 @@
+<html>
+  <body>
+    <a href="field.html">Field Visualization</a><br>
+    <a href="plotter.html">Plots</a>
+  </body>
+</html>
diff --git a/y2024_defense/www/plotter.html b/y2024_defense/www/plotter.html
new file mode 100644
index 0000000..629ceaa
--- /dev/null
+++ b/y2024_defense/www/plotter.html
@@ -0,0 +1,7 @@
+<html>
+  <head>
+    <script src="plot_index_bundle.min.js" defer></script>
+  </head>
+  <body>
+  </body>
+</html>
diff --git a/y2024_defense/www/styles.css b/y2024_defense/www/styles.css
new file mode 100644
index 0000000..c2c44d2
--- /dev/null
+++ b/y2024_defense/www/styles.css
@@ -0,0 +1,74 @@
+.channel {
+  display: flex;
+  border-bottom: 1px solid;
+  font-size: 24px;
+}
+#field {
+  display: inline-block
+}
+
+#readouts,
+#middle_readouts
+{
+  display: inline-block;
+  vertical-align: top;
+  float: right;
+}
+
+
+#legend {
+  display: inline-block;
+}
+
+table, th, td {
+  border: 1px solid black;
+  border-collapse: collapse;
+  padding: 5px;
+  margin: 10px;
+}
+
+th, td {
+  text-align: right;
+  width: 70px;
+}
+
+td:first-child {
+  width: 150px;
+}
+
+.connected, .near {
+  background-color: LightGreen;
+  border-radius: 10px;
+}
+
+.zeroing {
+  background-color: yellow;
+  border-radius: 10px;
+}
+
+.faulted {
+  background-color: red;
+  border-radius: 10px;
+}
+
+#vision_readouts > div {
+  display: table-row;
+  padding: 5px;
+}
+
+#vision_readouts > div > div {
+  display: table-cell;
+  padding: 5px;
+  text-align: right;
+}
+
+#message_bridge_status > div {
+  display: table-row;
+  padding: 5px;
+}
+
+#message_bridge_status > div > div {
+  display: table-cell;
+  padding: 5px;
+  text-align: right;
+}
diff --git a/y2024_defense/y2024_defense.json b/y2024_defense/y2024_defense.json
new file mode 100644
index 0000000..03e7373
--- /dev/null
+++ b/y2024_defense/y2024_defense.json
@@ -0,0 +1,18 @@
+{
+  "channel_storage_duration": 10000000000,
+  "maps": [
+    {
+      "match": {
+        "name": "/aos",
+        "type": "aos.RobotState"
+      },
+      "rename": {
+        "name": "/roborio/aos"
+      }
+    }
+  ],
+  "imports": [
+    "y2024_defense_roborio.json",
+    "y2024_defense_imu.json",
+  ]
+}
diff --git a/y2024_defense/y2024_defense_imu.json b/y2024_defense/y2024_defense_imu.json
new file mode 100644
index 0000000..1d64398
--- /dev/null
+++ b/y2024_defense/y2024_defense_imu.json
@@ -0,0 +1,280 @@
+{
+  "channels": [
+    {
+      "name": "/imu/aos",
+      "type": "aos.JoystickState",
+      "source_node": "imu",
+      "frequency": 100,
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+          "roborio"
+      ]
+    },
+    {
+      "name": "/imu/aos",
+      "type": "aos.timing.Report",
+      "source_node": "imu",
+      "frequency": 50,
+      "num_senders": 20,
+      "max_size": 4096
+    },
+    {
+      "name": "/imu/aos",
+      "type": "aos.logging.LogMessageFbs",
+      "source_node": "imu",
+      "frequency": 200,
+      "num_senders": 20
+    },
+    {
+      "name": "/imu/aos",
+      "type": "aos.starter.Status",
+      "source_node": "imu",
+      "frequency": 50,
+      "num_senders": 20,
+      "max_size": 2048
+    },
+    {
+      "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": "LOCAL_AND_REMOTE_LOGGER",
+      "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": "/localizer",
+      "type": "frc971.IMUValuesBatch",
+      "source_node": "imu",
+      "frequency": 2200,
+      "max_size": 1600,
+      "num_senders": 2
+    },
+    {
+      "name": "/localizer",
+      "type": "frc971.controls.LocalizerOutput",
+      "source_node": "imu",
+      "frequency": 52,
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "roborio"
+      ],
+      "destination_nodes": [
+        {
+          "name": "roborio",
+          "priority": 5,
+          "time_to_live": 5000000,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "imu"
+          ]
+        }
+      ]
+    },
+    {
+      "name": "/imu/aos/remote_timestamps/roborio/localizer/frc971-controls-LocalizerOutput",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "imu",
+      "logger": "NOT_LOGGED",
+      "frequency": 52,
+      "num_senders": 2,
+      "max_size": 200
+    },
+  ],
+  "applications": [
+    {
+      "name": "message_bridge_client",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "localizer",
+      "executable_name": "localizer_main",
+      "user": "pi",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "imu",
+      "executable_name": "imu_main",
+      "user": "pi",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "joystick_republish",
+      "executable_name": "joystick_republish",
+      "user": "pi",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "message_bridge_server",
+      "executable_name": "message_bridge_server",
+      "user": "pi",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "localizer_logger",
+      "executable_name": "logger_main",
+      "args": [
+        "--logging_folder",
+        "",
+        "--snappy_compress",
+        "--rotate_every", "30.0"
+      ],
+      "user": "pi",
+      "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"
+      ]
+    }
+  ],
+  "maps": [
+    {
+      "match": {
+        "name": "/constants*",
+        "source_node": "imu"
+      },
+      "rename": {
+        "name": "/imu/constants"
+      }
+    },
+    {
+      "match": {
+        "name": "/aos*",
+        "source_node": "imu"
+      },
+      "rename": {
+        "name": "/imu/aos"
+      }
+    }
+  ],
+  "nodes": [
+    {
+      "name": "imu",
+      "hostname": "pi6",
+      "hostnames": [
+        "pi-971-6",
+        "pi-7971-6",
+        "pi-8971-6",
+        "pi-9971-6"
+      ],
+      "port": 9971
+    },
+    {
+      "name": "roborio"
+    },
+  ]
+}
diff --git a/y2024_defense/y2024_defense_roborio.json b/y2024_defense/y2024_defense_roborio.json
new file mode 100644
index 0000000..f397de3
--- /dev/null
+++ b/y2024_defense/y2024_defense_roborio.json
@@ -0,0 +1,385 @@
+{
+  "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": "aos.RobotState",
+      "source_node": "roborio",
+      "frequency": 250
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "aos.timing.Report",
+      "source_node": "roborio",
+      "frequency": 50,
+      "num_senders": 20,
+      "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": "/can",
+      "type": "frc971.can_logger.CanFrame",
+      "source_node": "roborio",
+      "frequency": 6000,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
+      "name": "/drivetrain",
+      "type": "frc971.control_loops.drivetrain.CANPosition",
+      "source_node": "roborio",
+      "frequency": 220,
+      "num_senders": 2,
+      "max_size": 400
+    },
+    {
+      "name": "/drivetrain",
+      "type": "frc971.sensors.GyroReading",
+      "source_node": "roborio",
+      "frequency": 250,
+      "num_senders": 2
+    },
+    {
+      "name": "/drivetrain",
+      "type": "frc971.sensors.Uid",
+      "source_node": "roborio",
+      "frequency": 250,
+      "num_senders": 2
+    },
+    {
+      "name": "/drivetrain",
+      "type": "frc971.control_loops.drivetrain.fb.Trajectory",
+      "source_node": "roborio",
+      "max_size": 600000,
+      "frequency": 10,
+      "logger": "NOT_LOGGED",
+      "num_senders": 2,
+      "read_method": "PIN",
+      "num_readers": 10
+    },
+    {
+      "name": "/drivetrain",
+      "type": "frc971.control_loops.drivetrain.SplineGoal",
+      "source_node": "roborio",
+      "frequency": 10
+    },
+    {
+      "name": "/drivetrain",
+      "type": "frc971.control_loops.drivetrain.Goal",
+      "source_node": "roborio",
+      "max_size": 224,
+      "frequency": 250
+    },
+    {
+      "name": "/drivetrain",
+      "type": "frc971.control_loops.drivetrain.Position",
+      "source_node": "roborio",
+      "frequency": 400,
+      "max_size": 112,
+      "num_senders": 2
+    },
+    {
+      "name": "/drivetrain",
+      "type": "frc971.control_loops.drivetrain.Output",
+      "source_node": "roborio",
+      "frequency": 400,
+      "max_size": 80,
+      "num_senders": 2,
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "imu"
+      ],
+      "destination_nodes": [
+        {
+          "name": "imu",
+          "priority": 5,
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/drivetrain",
+      "type": "frc971.control_loops.drivetrain.Status",
+      "source_node": "roborio",
+      "frequency": 400,
+      "max_size": 1616,
+      "num_senders": 2
+    },
+    {
+      "name": "/drivetrain",
+      "type": "frc971.control_loops.drivetrain.LocalizerControl",
+      "source_node": "roborio",
+      "frequency": 250,
+      "max_size": 96,
+      "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": 0
+        }
+      ]
+    },
+    {
+      "name": "/roborio/aos/remote_timestamps/imu/drivetrain/frc971-control_loops-drivetrain-LocalizerControl",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "roborio",
+      "logger": "NOT_LOGGED",
+      "frequency": 400,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
+      "name": "/autonomous",
+      "type": "aos.common.actions.Status",
+      "source_node": "roborio"
+    },
+    {
+      "name": "/autonomous",
+      "type": "frc971.autonomous.Goal",
+      "source_node": "roborio"
+    },
+    {
+      "name": "/autonomous",
+      "type": "frc971.autonomous.AutonomousMode",
+      "source_node": "roborio",
+      "frequency": 250
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "frc971.PDPValues",
+      "source_node": "roborio",
+      "frequency": 55,
+      "max_size": 368
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "frc971.wpilib.PneumaticsToLog",
+      "source_node": "roborio",
+      "frequency": 50
+    },
+    {
+      "name": "/roborio",
+      "type": "frc971.CANConfiguration",
+      "source_node": "roborio",
+      "frequency": 2
+    },
+  ],
+  "applications": [
+    {
+      "name": "drivetrain",
+      "executable_name": "drivetrain",
+      "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"
+      ],
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "roborio_message_bridge_server",
+      "executable_name": "message_bridge_server",
+      "args": [
+        "--rt_priority=16"
+      ],
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "logger",
+      "executable_name": "logger_main",
+      "args": [
+        "--snappy_compress",
+        "--logging_folder=/home/admin/logs/",
+        "--rotate_every", "30.0"
+      ],
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "can_logger",
+      "executable_name": "can_logger",
+      "nodes": [
+        "roborio"
+      ]
+    }
+  ],
+  "maps": [
+    {
+      "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-9972-FRC"
+      ],
+      "port": 9972
+    },
+    {
+      "name": "imu"
+    }
+  ]
+}