Add code for swerve drivebase experiments

Signed-off-by: Maxwell Henderson <maxwell.henderson@mailbox.org>
Change-Id: I24701125e0826d46845cc85abdae8dff52b7c678
diff --git a/y2023_bot4/BUILD b/y2023_bot4/BUILD
new file mode 100644
index 0000000..1a4ed64
--- /dev/null
+++ b/y2023_bot4/BUILD
@@ -0,0 +1,234 @@
+load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
+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 = "//y2023_bot4:aos_config",
+)
+
+robot_downloader(
+    binaries = [
+        "//aos/network:web_proxy_main",
+        "//aos/events/logging:log_cat",
+        "//aos/events:aos_timing_report_streamer",
+    ],
+    data = [
+        ":aos_config",
+        ":swerve_publisher_output_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",
+    ],
+    start_binaries = [
+        "//aos/events/logging:logger_main",
+        "//aos/network:web_proxy_main",
+        "//aos/starter:irq_affinity",
+        ":wpilib_interface",
+        ":swerve_publisher",
+        "//frc971/can_logger",
+        "//aos/network:message_bridge_client",
+        "//aos/network:message_bridge_server",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+)
+
+robot_downloader(
+    name = "pi_download",
+    binaries = [
+        "//aos/util:foxglove_websocket",
+        "//aos/events:aos_timing_report_streamer",
+        "//aos/events/logging:log_cat",
+        "//y2023/rockpi:imu_main",
+        "//frc971/image_streamer:image_streamer",
+        "//aos/network:message_bridge_client",
+        "//aos/network:message_bridge_server",
+        "//aos/network:web_proxy_main",
+        "//aos/starter:irq_affinity",
+        "//aos/events/logging:logger_main",
+    ],
+    data = [
+        ":aos_config",
+        "//frc971/rockpi:rockpi_config.json",
+    ],
+    start_binaries = [
+    ],
+    target_compatible_with = ["//tools/platforms/hardware:raspberry_pi"],
+    target_type = "pi",
+)
+
+filegroup(
+    name = "swerve_publisher_output_json",
+    srcs = [
+        "swerve_drivetrain_output.json",
+    ],
+    visibility = ["//y2023_bot4:__subpackages__"],
+)
+
+cc_library(
+    name = "constants",
+    srcs = ["constants.cc"],
+    hdrs = [
+        "constants.h",
+    ],
+    visibility = ["//visibility:public"],
+    deps = [
+        "//aos/network:team_number",
+        "//frc971:constants",
+    ],
+)
+
+flatbuffer_cc_library(
+    name = "drivetrain_position_fbs",
+    srcs = ["drivetrain_position.fbs"],
+    gen_reflections = 1,
+    deps = ["//frc971/control_loops:control_loops_fbs"],
+)
+
+flatbuffer_cc_library(
+    name = "drivetrain_can_position_fbs",
+    srcs = ["drivetrain_can_position.fbs"],
+    gen_reflections = 1,
+    deps = ["//frc971/control_loops:can_falcon_fbs"],
+)
+
+cc_binary(
+    name = "swerve_publisher",
+    srcs = ["swerve_publisher_main.cc"],
+    deps = [
+        ":swerve_publisher_lib",
+        "//aos/events:shm_event_loop",
+        "@com_github_gflags_gflags//:gflags",
+    ],
+)
+
+cc_library(
+    name = "swerve_publisher_lib",
+    srcs = ["swerve_publisher_lib.cc"],
+    hdrs = ["swerve_publisher_lib.h"],
+    deps = [
+        "//aos:init",
+        "//aos/events:event_loop",
+        "//frc971/control_loops/drivetrain/swerve:swerve_drivetrain_output_fbs",
+        "@com_github_google_glog//:glog",
+    ],
+)
+
+cc_test(
+    name = "swerve_publisher_lib_test",
+    srcs = [
+        "swerve_publisher_lib_test.cc",
+    ],
+    data = [
+        ":aos_config",
+        ":swerve_publisher_output_json",
+    ],
+    deps = [
+        ":swerve_publisher_lib",
+        "//aos/events:simulated_event_loop",
+        "//aos/testing:googletest",
+    ],
+)
+
+cc_binary(
+    name = "wpilib_interface",
+    srcs = ["wpilib_interface.cc"],
+    target_compatible_with = ["//tools/platforms/hardware:roborio"],
+    deps = [
+        ":constants",
+        ":drivetrain_can_position_fbs",
+        ":drivetrain_position_fbs",
+        "//aos:init",
+        "//aos/events:shm_event_loop",
+        "//frc971/control_loops:control_loops_fbs",
+        "//frc971/wpilib:can_sensor_reader",
+        "//frc971/wpilib:falcon",
+        "//frc971/wpilib:sensor_reader",
+        "//frc971/wpilib:wpilib_robot_base",
+        "//frc971/wpilib/swerve:swerve_drivetrain_writer",
+    ],
+)
+
+aos_config(
+    name = "aos_config",
+    src = "y2023_bot4.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_logger",
+        ":config_roborio",
+    ],
+)
+
+aos_config(
+    name = "config_roborio",
+    src = "y2023_bot4_roborio.json",
+    flatbuffers = [
+        ":drivetrain_position_fbs",
+        ":drivetrain_can_position_fbs",
+        "//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/swerve:swerve_drivetrain_output_fbs",
+        "//frc971/control_loops/drivetrain/swerve:swerve_drivetrain_position_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",
+    ],
+)
+
+aos_config(
+    name = "config_imu",
+    src = "y2023_bot4_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/vision:target_map_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_logger",
+    src = "y2023_bot4_logger.json",
+    flatbuffers = [
+        "//aos/network:message_bridge_client_fbs",
+        "//aos/network:message_bridge_server_fbs",
+        "//aos/network:timestamp_fbs",
+        "//aos/network:remote_message_fbs",
+        "//frc971/vision:calibration_fbs",
+        "//frc971/vision:target_map_fbs",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+    deps = [
+        "//aos/events:aos_config",
+        "//frc971/control_loops/drivetrain:aos_config",
+        "//frc971/input:aos_config",
+    ],
+)
diff --git a/y2023_bot4/constants.cc b/y2023_bot4/constants.cc
new file mode 100644
index 0000000..aab1935
--- /dev/null
+++ b/y2023_bot4/constants.cc
@@ -0,0 +1,52 @@
+#include "y2023_bot4/constants.h"
+
+#include <cstdint>
+
+#include "glog/logging.h"
+
+#include "aos/network/team_number.h"
+
+namespace y2023_bot4 {
+namespace constants {
+Values MakeValues(uint16_t team) {
+  LOG(INFO) << "creating a Constants for team: " << team;
+  Values r;
+  auto *const front_left_zeroing_constants = &r.front_left_zeroing_constants;
+  auto *const front_right_zeroing_constants = &r.front_right_zeroing_constants;
+  auto *const back_left_zeroing_constants = &r.back_left_zeroing_constants;
+  auto *const back_right_zeroing_constants = &r.back_right_zeroing_constants;
+
+  front_left_zeroing_constants->average_filter_size = 0;
+  front_left_zeroing_constants->one_revolution_distance = 2 * M_PI;
+  front_left_zeroing_constants->measured_absolute_position = 0.76761395509829;
+  front_left_zeroing_constants->zeroing_threshold = 0.0;
+  front_left_zeroing_constants->moving_buffer_size = 0.0;
+  front_left_zeroing_constants->allowable_encoder_error = 0.0;
+
+  front_right_zeroing_constants->average_filter_size = 0;
+  front_right_zeroing_constants->one_revolution_distance = 2 * M_PI;
+  front_right_zeroing_constants->measured_absolute_position = 0.779403958443922;
+  front_right_zeroing_constants->zeroing_threshold = 0.0;
+  front_right_zeroing_constants->moving_buffer_size = 0.0;
+  front_right_zeroing_constants->allowable_encoder_error = 0.0;
+
+  back_left_zeroing_constants->average_filter_size = 0;
+  back_left_zeroing_constants->one_revolution_distance = 2 * M_PI;
+  back_left_zeroing_constants->measured_absolute_position = 0.053439698061417;
+  back_left_zeroing_constants->zeroing_threshold = 0.0;
+  back_left_zeroing_constants->moving_buffer_size = 0.0;
+  back_left_zeroing_constants->allowable_encoder_error = 0.0;
+
+  back_right_zeroing_constants->average_filter_size = 0;
+  back_right_zeroing_constants->one_revolution_distance = 2 * M_PI;
+  back_right_zeroing_constants->measured_absolute_position = 0.719329333121509;
+  back_right_zeroing_constants->zeroing_threshold = 0.0;
+  back_right_zeroing_constants->moving_buffer_size = 0.0;
+  back_right_zeroing_constants->allowable_encoder_error = 0.0;
+
+  return r;
+}
+
+Values MakeValues() { return MakeValues(aos::network::GetTeamNumber()); }
+}  // namespace constants
+}  // namespace y2023_bot4
diff --git a/y2023_bot4/constants.h b/y2023_bot4/constants.h
new file mode 100644
index 0000000..676ae06
--- /dev/null
+++ b/y2023_bot4/constants.h
@@ -0,0 +1,55 @@
+#ifndef Y2023_BOT4_CONSTANTS_H
+#define Y2023_BOT4_CONSTANTS_H
+
+#ifndef M_PI
+#define M_PI 3.14159265358979323846
+#endif
+
+#include <cstdint>
+
+#include "frc971/constants.h"
+
+namespace y2023_bot4 {
+namespace constants {
+struct Values {
+  static const int kZeroingSampleSize = 200;
+
+  static const int kDrivetrainWriterPriority = 35;
+  static const int kDrivetrainTxPriority = 36;
+  static const int kDrivetrainRxPriority = 36;
+
+  // TODO (maxwell): Make this the real value;
+  static constexpr double kDrivetrainCyclesPerRevolution() { return 512.0; }
+  static constexpr double kDrivetrainEncoderRatio() { return 1.0; }
+
+  static constexpr double kDrivetrainStatorCurrentLimit() { return 35.0; }
+  static constexpr double kDrivetrainSupplyCurrentLimit() { return 60.0; }
+
+  // TODO (maxwell): Make this the real value
+  static constexpr double kFollowerWheelCountsPerRevolution() { return 512.0; }
+  static constexpr double kFollowerWheelEncoderRatio() { return 1.0; }
+  static constexpr double kFollowerWheelRadius() { return 3.25 / 2 * 0.0254; }
+  static constexpr double kDrivetrainEncoderCountsPerRevolution() {
+    return 2048.0;
+  }
+
+  static constexpr double kMaxDrivetrainEncoderPulsesPerSecond() {
+    return 1200000;
+  }
+
+  frc971::constants::ContinuousAbsoluteEncoderZeroingConstants
+      front_left_zeroing_constants,
+      front_right_zeroing_constants, back_left_zeroing_constants,
+      back_right_zeroing_constants;
+};
+// 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 y2023_bot4
+
+#endif  // Y2023_BOT4_CONSTANTS_H
diff --git a/y2023_bot4/drivetrain_can_position.fbs b/y2023_bot4/drivetrain_can_position.fbs
new file mode 100644
index 0000000..e8c1235
--- /dev/null
+++ b/y2023_bot4/drivetrain_can_position.fbs
@@ -0,0 +1,17 @@
+include "frc971/control_loops/can_falcon.fbs";
+namespace y2023_bot4;
+
+table SwerveModuleCANPosition {
+  rotation: frc971.control_loops.CANFalcon (id: 0);
+  translation: frc971.control_loops.CANFalcon (id: 1);
+}
+
+// CAN Readings from the CAN sensor reader loop for each swerve module
+table AbsoluteCANPosition {
+  front_left: SwerveModuleCANPosition (id: 0);
+  front_right: SwerveModuleCANPosition (id: 1);
+  back_left: SwerveModuleCANPosition (id: 2);
+  back_right: SwerveModuleCANPosition (id: 3);
+}
+
+root_type AbsoluteCANPosition;
diff --git a/y2023_bot4/drivetrain_position.fbs b/y2023_bot4/drivetrain_position.fbs
new file mode 100644
index 0000000..e5d0fc3
--- /dev/null
+++ b/y2023_bot4/drivetrain_position.fbs
@@ -0,0 +1,16 @@
+include "frc971/control_loops/control_loops.fbs";
+namespace y2023_bot4;
+
+table AbsoluteDrivetrainPosition {
+  // Position of the follower wheels from the encoders
+  follower_wheel_one_position:double (id: 0);
+  follower_wheel_two_position:double (id: 1);
+
+  // Position from the mag encoder on each module.
+  front_left_position: frc971.AbsolutePosition (id: 2);
+  front_right_position: frc971.AbsolutePosition (id: 3);
+  back_left_position: frc971.AbsolutePosition (id: 4);
+  back_right_position: frc971.AbsolutePosition  (id: 5);
+}
+
+root_type AbsoluteDrivetrainPosition;
diff --git a/y2023_bot4/swerve_drivetrain_output.json b/y2023_bot4/swerve_drivetrain_output.json
new file mode 100644
index 0000000..bc152e2
--- /dev/null
+++ b/y2023_bot4/swerve_drivetrain_output.json
@@ -0,0 +1,18 @@
+{
+    "front_left_output": {
+        "rotation_current": 0.0,
+        "translation_current": 0.0
+    },
+    "front_right_output": {
+        "rotation_current": 0.0,
+        "translation_current": 0.0
+    },
+    "back_left_output": {
+        "rotation_current": 0.0,
+        "translation_current": 0.0
+    },
+    "back_right_output": {
+        "rotation_current": 0.0,
+        "translation_current": 0.0
+    }
+}
diff --git a/y2023_bot4/swerve_publisher_lib.cc b/y2023_bot4/swerve_publisher_lib.cc
new file mode 100644
index 0000000..78a778e
--- /dev/null
+++ b/y2023_bot4/swerve_publisher_lib.cc
@@ -0,0 +1,51 @@
+#include "y2023_bot4/swerve_publisher_lib.h"
+
+y2023_bot4::SwervePublisher::SwervePublisher(aos::EventLoop *event_loop,
+                                             aos::ExitHandle *exit_handle,
+                                             const std::string &filename,
+                                             double duration)
+    : drivetrain_output_sender_(
+          event_loop->MakeSender<drivetrain::swerve::Output>("/drivetrain")) {
+  event_loop
+      ->AddTimer([this, filename]() {
+        auto output_builder = drivetrain_output_sender_.MakeBuilder();
+
+        auto drivetrain_output =
+            aos::JsonFileToFlatbuffer<drivetrain::swerve::Output>(filename);
+
+        auto copied_flatbuffer =
+            aos::CopyFlatBuffer<drivetrain::swerve::Output>(
+                drivetrain_output, output_builder.fbb());
+        CHECK(drivetrain_output.Verify());
+
+        output_builder.CheckOk(output_builder.Send(copied_flatbuffer));
+      })
+      ->Schedule(event_loop->monotonic_now(),
+                 std::chrono::duration_cast<aos::monotonic_clock::duration>(
+                     std::chrono::milliseconds(5)));
+  event_loop
+      ->AddTimer([this, exit_handle]() {
+        auto builder = drivetrain_output_sender_.MakeBuilder();
+        drivetrain::swerve::SwerveModuleOutput::Builder swerve_module_builder =
+            builder.MakeBuilder<drivetrain::swerve::SwerveModuleOutput>();
+
+        swerve_module_builder.add_rotation_current(0.0);
+        swerve_module_builder.add_translation_current(0.0);
+
+        auto swerve_module_offset = swerve_module_builder.Finish();
+
+        drivetrain::swerve::Output::Builder drivetrain_output_builder =
+            builder.MakeBuilder<drivetrain::swerve::Output>();
+
+        drivetrain_output_builder.add_front_left_output(swerve_module_offset);
+        drivetrain_output_builder.add_front_right_output(swerve_module_offset);
+        drivetrain_output_builder.add_back_left_output(swerve_module_offset);
+        drivetrain_output_builder.add_back_right_output(swerve_module_offset);
+
+        builder.CheckOk(builder.Send(drivetrain_output_builder.Finish()));
+
+        exit_handle->Exit();
+      })
+      ->Schedule(event_loop->monotonic_now() +
+                 std::chrono::milliseconds((int)duration));
+}
diff --git a/y2023_bot4/swerve_publisher_lib.h b/y2023_bot4/swerve_publisher_lib.h
new file mode 100644
index 0000000..5969b7b
--- /dev/null
+++ b/y2023_bot4/swerve_publisher_lib.h
@@ -0,0 +1,29 @@
+#ifndef Y2023_BOT4_SWERVE_PUBLISHER_H_
+#define Y2023_BOT4_SWERVE_PUBLISHER_H_
+
+#include "gflags/gflags.h"
+#include "glog/logging.h"
+
+#include "aos/events/event_loop.h"
+#include "aos/flatbuffer_merge.h"
+#include "aos/init.h"
+#include "aos/json_to_flatbuffer.h"
+#include "frc971/control_loops/drivetrain/swerve/swerve_drivetrain_output_generated.h"
+
+namespace y2023_bot4 {
+
+namespace drivetrain = frc971::control_loops::drivetrain;
+
+class SwervePublisher {
+ public:
+  SwervePublisher(aos::EventLoop *event_loop, aos::ExitHandle *exit_handle,
+                  const std::string &filename, double duration);
+
+ private:
+  aos::Sender<frc971::control_loops::drivetrain::swerve::Output>
+      drivetrain_output_sender_;
+};
+
+}  // namespace y2023_bot4
+
+#endif  // Y2023_BOT4_SWERVE_PUBLISHER_H_
diff --git a/y2023_bot4/swerve_publisher_lib_test.cc b/y2023_bot4/swerve_publisher_lib_test.cc
new file mode 100644
index 0000000..817f295
--- /dev/null
+++ b/y2023_bot4/swerve_publisher_lib_test.cc
@@ -0,0 +1,54 @@
+#include "y2023_bot4/swerve_publisher_lib.h"
+
+#include "gtest/gtest.h"
+
+#include "aos/events/simulated_event_loop.h"
+
+namespace y2023_bot4 {
+namespace testing {
+class SwervePublisherTest : public ::testing::Test {
+ public:
+  SwervePublisherTest()
+      : config_(aos::configuration::ReadConfig("y2023_bot4/aos_config.json")),
+        event_loop_factory_(&config_.message()),
+        roborio_(aos::configuration::GetNode(
+            event_loop_factory_.configuration(), "roborio")),
+        event_loop_(
+            event_loop_factory_.MakeEventLoop("swerve_publisher", roborio_)),
+        exit_handle_(event_loop_factory_.MakeExitHandle()),
+        drivetrain_swerve_output_fetcher_(
+            event_loop_->MakeFetcher<
+                frc971::control_loops::drivetrain::swerve::Output>(
+                "/drivetrain")),
+        swerve_publisher_(event_loop_.get(), exit_handle_.get(),
+                          "y2023_bot4/swerve_drivetrain_output.json", 100) {}
+
+  void SendOutput() { event_loop_factory_.Run(); }
+
+  void CheckOutput() {
+    drivetrain_swerve_output_fetcher_.Fetch();
+
+    ASSERT_TRUE(drivetrain_swerve_output_fetcher_.get() != nullptr)
+        << ": No drivetrain output";
+  }
+
+ private:
+  aos::FlatbufferDetachedBuffer<aos::Configuration> config_;
+  aos::SimulatedEventLoopFactory event_loop_factory_;
+  const aos::Node *const roborio_;
+
+  std::unique_ptr<aos::EventLoop> event_loop_;
+  std::unique_ptr<aos::ExitHandle> exit_handle_;
+
+  aos::Fetcher<frc971::control_loops::drivetrain::swerve::Output>
+      drivetrain_swerve_output_fetcher_;
+
+  y2023_bot4::SwervePublisher swerve_publisher_;
+};
+
+TEST_F(SwervePublisherTest, CheckSentFb) {
+  SendOutput();
+  CheckOutput();
+}
+}  // namespace testing
+}  // namespace y2023_bot4
diff --git a/y2023_bot4/swerve_publisher_main.cc b/y2023_bot4/swerve_publisher_main.cc
new file mode 100644
index 0000000..87470d7
--- /dev/null
+++ b/y2023_bot4/swerve_publisher_main.cc
@@ -0,0 +1,24 @@
+#include "aos/events/shm_event_loop.h"
+#include "y2023_bot4/swerve_publisher_lib.h"
+
+DEFINE_double(duration, 100.0, "Length of time in Ms to apply current for");
+DEFINE_string(drivetrain_position, "swerve_drivetrain_output.json",
+              "The path to the json drivetrain position to apply");
+DEFINE_string(config, "aos_config.json", "The path to aos_config.json");
+
+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());
+
+  std::unique_ptr<aos::ExitHandle> exit_handle = event_loop.MakeExitHandle();
+
+  y2023_bot4::SwervePublisher publisher(&event_loop, exit_handle.get(),
+                                        FLAGS_drivetrain_position,
+                                        FLAGS_duration);
+
+  event_loop.Run();
+}
diff --git a/y2023_bot4/wpilib_interface.cc b/y2023_bot4/wpilib_interface.cc
new file mode 100644
index 0000000..a744ae0
--- /dev/null
+++ b/y2023_bot4/wpilib_interface.cc
@@ -0,0 +1,325 @@
+#include "ctre/phoenix/cci/Diagnostics_CCI.h"
+#include "ctre/phoenix6/TalonFX.hpp"
+
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "frc971/control_loops/control_loops_generated.h"
+#include "frc971/wpilib/can_sensor_reader.h"
+#include "frc971/wpilib/falcon.h"
+#include "frc971/wpilib/sensor_reader.h"
+#include "frc971/wpilib/swerve/swerve_drivetrain_writer.h"
+#include "frc971/wpilib/wpilib_robot_base.h"
+#include "y2023_bot4/constants.h"
+#include "y2023_bot4/drivetrain_can_position_generated.h"
+#include "y2023_bot4/drivetrain_position_generated.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 frc971::wpilib::CANSensorReader;
+using frc971::wpilib::Falcon;
+using frc971::wpilib::swerve::DrivetrainWriter;
+using frc971::wpilib::swerve::SwerveModule;
+
+namespace drivetrain = frc971::control_loops::drivetrain;
+
+namespace y2023_bot4 {
+namespace wpilib {
+namespace {
+
+template <class T>
+T value_or_exit(std::optional<T> optional) {
+  CHECK(optional.has_value());
+  return optional.value();
+}
+
+flatbuffers::Offset<frc971::AbsolutePosition> module_offset(
+    frc971::AbsolutePosition::Builder builder,
+    frc971::wpilib::AbsoluteEncoder *module) {
+  builder.add_encoder(module->ReadRelativeEncoder());
+  builder.add_absolute_encoder(module->ReadAbsoluteEncoder());
+
+  return builder.Finish();
+}
+
+flatbuffers::Offset<SwerveModuleCANPosition> can_module_offset(
+    SwerveModuleCANPosition::Builder builder,
+    std::shared_ptr<SwerveModule> module) {
+  std::optional<flatbuffers::Offset<control_loops::CANFalcon>> rotation_offset =
+      module->rotation->TakeOffset();
+  std::optional<flatbuffers::Offset<control_loops::CANFalcon>>
+      translation_offset = module->translation->TakeOffset();
+
+  CHECK(rotation_offset.has_value());
+  CHECK(translation_offset.has_value());
+
+  builder.add_rotation(rotation_offset.value());
+  builder.add_translation(translation_offset.value());
+
+  return builder.Finish();
+}
+
+constexpr double kMaxFastEncoderPulsesPerSecond = std::max({
+    constants::Values::kMaxDrivetrainEncoderPulsesPerSecond(),
+});
+static_assert(kMaxFastEncoderPulsesPerSecond <= 1300000,
+              "fast encoders are too fast");
+}  // namespace
+
+class SensorReader : public ::frc971::wpilib::SensorReader {
+ public:
+  SensorReader(aos::ShmEventLoop *event_loop,
+               std::shared_ptr<const constants::Values> values)
+      : ::frc971::wpilib::SensorReader(event_loop),
+        values_(values),
+        drivetrain_position_sender_(
+            event_loop->MakeSender<AbsoluteDrivetrainPosition>("/drivetrain")) {
+    UpdateFastEncoderFilterHz(kMaxFastEncoderPulsesPerSecond);
+    event_loop->SetRuntimeAffinity(aos::MakeCpusetFromCpus({0}));
+  }
+
+  void RunIteration() override {
+    {
+      auto builder = drivetrain_position_sender_.MakeBuilder();
+
+      auto front_left_offset =
+          module_offset(builder.MakeBuilder<frc971::AbsolutePosition>(),
+                        &front_left_encoder_);
+      auto front_right_offset =
+          module_offset(builder.MakeBuilder<frc971::AbsolutePosition>(),
+                        &front_right_encoder_);
+      auto back_left_offset = module_offset(
+          builder.MakeBuilder<frc971::AbsolutePosition>(), &back_left_encoder_);
+      auto back_right_offset =
+          module_offset(builder.MakeBuilder<frc971::AbsolutePosition>(),
+                        &back_right_encoder_);
+
+      AbsoluteDrivetrainPosition::Builder drivetrain_position_builder =
+          builder.MakeBuilder<AbsoluteDrivetrainPosition>();
+
+      drivetrain_position_builder.add_follower_wheel_one_position(
+          follower_wheel_one_encoder_->GetRaw());
+      drivetrain_position_builder.add_follower_wheel_two_position(
+          follower_wheel_two_encoder_->GetRaw());
+
+      drivetrain_position_builder.add_front_left_position(front_left_offset);
+      drivetrain_position_builder.add_front_right_position(front_right_offset);
+      drivetrain_position_builder.add_back_left_position(back_left_offset);
+      drivetrain_position_builder.add_back_right_position(back_right_offset);
+
+      builder.CheckOk(builder.Send(drivetrain_position_builder.Finish()));
+    }
+  }
+
+  void set_follower_wheel_one_encoder(std::unique_ptr<frc::Encoder> encoder) {
+    fast_encoder_filter_.Add(encoder.get());
+    follower_wheel_one_encoder_ = std::move(encoder);
+    follower_wheel_one_encoder_->SetMaxPeriod(0.005);
+  }
+  void set_follower_wheel_two_encoder(std::unique_ptr<frc::Encoder> encoder) {
+    fast_encoder_filter_.Add(encoder.get());
+    follower_wheel_two_encoder_ = std::move(encoder);
+    follower_wheel_two_encoder_->SetMaxPeriod(0.005);
+  }
+
+  void set_front_left_encoder(std::unique_ptr<frc::Encoder> encoder) {
+    fast_encoder_filter_.Add(encoder.get());
+    front_left_encoder_.set_encoder(std::move(encoder));
+  }
+  void set_front_left_absolute_pwm(
+      std::unique_ptr<frc::DigitalInput> absolute_pwm) {
+    front_left_encoder_.set_absolute_pwm(std::move(absolute_pwm));
+  }
+
+  void set_front_right_encoder(std::unique_ptr<frc::Encoder> encoder) {
+    fast_encoder_filter_.Add(encoder.get());
+    front_right_encoder_.set_encoder(std::move(encoder));
+  }
+  void set_front_right_absolute_pwm(
+      std::unique_ptr<frc::DigitalInput> absolute_pwm) {
+    front_right_encoder_.set_absolute_pwm(std::move(absolute_pwm));
+  }
+
+  void set_back_left_encoder(std::unique_ptr<frc::Encoder> encoder) {
+    fast_encoder_filter_.Add(encoder.get());
+    back_left_encoder_.set_encoder(std::move(encoder));
+  }
+  void set_back_left_absolute_pwm(
+      std::unique_ptr<frc::DigitalInput> absolute_pwm) {
+    back_left_encoder_.set_absolute_pwm(std::move(absolute_pwm));
+  }
+
+  void set_back_right_encoder(std::unique_ptr<frc::Encoder> encoder) {
+    fast_encoder_filter_.Add(encoder.get());
+    back_right_encoder_.set_encoder(std::move(encoder));
+  }
+  void set_back_right_absolute_pwm(
+      std::unique_ptr<frc::DigitalInput> absolute_pwm) {
+    back_right_encoder_.set_absolute_pwm(std::move(absolute_pwm));
+  }
+
+ private:
+  std::shared_ptr<const constants::Values> values_;
+
+  aos::Sender<AbsoluteDrivetrainPosition> drivetrain_position_sender_;
+
+  std::unique_ptr<frc::Encoder> follower_wheel_one_encoder_,
+      follower_wheel_two_encoder_;
+
+  frc971::wpilib::AbsoluteEncoder front_left_encoder_, front_right_encoder_,
+      back_left_encoder_, back_right_encoder_;
+};
+
+class WPILibRobot : public ::frc971::wpilib::WPILibRobotBase {
+ public:
+  ::std::unique_ptr<frc::Encoder> make_encoder(int index) {
+    return std::make_unique<frc::Encoder>(10 + index * 2, 11 + index * 2, false,
+                                          frc::Encoder::k4X);
+  }
+  void Run() override {
+    std::shared_ptr<const constants::Values> values =
+        std::make_shared<const constants::Values>(constants::MakeValues());
+
+    aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+        aos::configuration::ReadConfig("aos_config.json");
+
+    std::vector<ctre::phoenix6::BaseStatusSignal *> signals_registry;
+    std::vector<std::shared_ptr<Falcon>> falcons;
+
+    // TODO(max): Change the CanBus names with TalonFX software.
+    std::shared_ptr<SwerveModule> front_left = std::make_shared<SwerveModule>(
+        frc971::wpilib::FalconParams{6, false},
+        frc971::wpilib::FalconParams{5, false}, "Drivetrain Bus",
+        &signals_registry, constants::Values::kDrivetrainStatorCurrentLimit(),
+        constants::Values::kDrivetrainSupplyCurrentLimit());
+    std::shared_ptr<SwerveModule> front_right = std::make_shared<SwerveModule>(
+        frc971::wpilib::FalconParams{3, false},
+        frc971::wpilib::FalconParams{4, false}, "Drivetrain Bus",
+        &signals_registry, constants::Values::kDrivetrainStatorCurrentLimit(),
+        constants::Values::kDrivetrainSupplyCurrentLimit());
+    std::shared_ptr<SwerveModule> back_left = std::make_shared<SwerveModule>(
+        frc971::wpilib::FalconParams{8, false},
+        frc971::wpilib::FalconParams{7, false}, "Drivetrain Bus",
+        &signals_registry, constants::Values::kDrivetrainStatorCurrentLimit(),
+        constants::Values::kDrivetrainSupplyCurrentLimit());
+    std::shared_ptr<SwerveModule> back_right = std::make_shared<SwerveModule>(
+        frc971::wpilib::FalconParams{2, false},
+        frc971::wpilib::FalconParams{1, false}, "Drivetrain Bus",
+        &signals_registry, constants::Values::kDrivetrainStatorCurrentLimit(),
+        constants::Values::kDrivetrainSupplyCurrentLimit());
+
+    // Thread 1
+    aos::ShmEventLoop can_sensor_reader_event_loop(&config.message());
+    can_sensor_reader_event_loop.set_name("CANSensorReader");
+
+    falcons.push_back(front_left->rotation);
+    falcons.push_back(front_left->translation);
+
+    falcons.push_back(front_right->rotation);
+    falcons.push_back(front_right->translation);
+
+    falcons.push_back(back_left->rotation);
+    falcons.push_back(back_left->translation);
+
+    falcons.push_back(back_right->rotation);
+    falcons.push_back(back_right->translation);
+
+    aos::Sender<AbsoluteCANPosition> can_position_sender =
+        can_sensor_reader_event_loop.MakeSender<AbsoluteCANPosition>(
+            "/drivetrain");
+
+    CANSensorReader can_sensor_reader(
+        &can_sensor_reader_event_loop, std::move(signals_registry), falcons,
+        [this, falcons, front_left, front_right, back_left, back_right,
+         &can_position_sender](ctre::phoenix::StatusCode status) {
+          // TODO(max): use status properly in the flatbuffer.
+          (void)status;
+
+          auto builder = can_position_sender.MakeBuilder();
+
+          for (auto falcon : falcons) {
+            falcon->RefreshNontimesyncedSignals();
+            falcon->SerializePosition(builder.fbb(), 1.0);
+          }
+
+          auto front_left_offset = can_module_offset(
+              builder.MakeBuilder<SwerveModuleCANPosition>(), front_left);
+          auto front_right_offset = can_module_offset(
+              builder.MakeBuilder<SwerveModuleCANPosition>(), front_right);
+          auto back_left_offset = can_module_offset(
+              builder.MakeBuilder<SwerveModuleCANPosition>(), back_left);
+          auto back_right_offset = can_module_offset(
+              builder.MakeBuilder<SwerveModuleCANPosition>(), back_right);
+
+          AbsoluteCANPosition::Builder can_position_builder =
+              builder.MakeBuilder<AbsoluteCANPosition>();
+
+          can_position_builder.add_front_left(front_left_offset);
+          can_position_builder.add_front_right(front_right_offset);
+          can_position_builder.add_back_left(back_left_offset);
+          can_position_builder.add_back_right(back_right_offset);
+
+          builder.CheckOk(builder.Send(can_position_builder.Finish()));
+        });
+
+    AddLoop(&can_sensor_reader_event_loop);
+
+    // Thread 2
+    // Setup CAN
+    if (!FLAGS_ctre_diag_server) {
+      c_Phoenix_Diagnostics_SetSecondsToStart(-1);
+      c_Phoenix_Diagnostics_Dispose();
+    }
+
+    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 drivetrain_writer_event_loop(&config.message());
+    drivetrain_writer_event_loop.set_name("DrivetrainWriter");
+
+    DrivetrainWriter drivetrain_writer(
+        &drivetrain_writer_event_loop,
+        constants::Values::kDrivetrainWriterPriority, 12);
+
+    drivetrain_writer.set_falcons(front_left, front_right, back_left,
+                                  back_right);
+
+    AddLoop(&drivetrain_writer_event_loop);
+
+    // Thread 3
+    aos::ShmEventLoop sensor_reader_event_loop(&config.message());
+    sensor_reader_event_loop.set_name("SensorReader");
+    SensorReader sensor_reader(&sensor_reader_event_loop, values);
+
+    sensor_reader.set_follower_wheel_one_encoder(make_encoder(4));
+    sensor_reader.set_follower_wheel_two_encoder(make_encoder(5));
+
+    sensor_reader.set_front_left_encoder(make_encoder(1));
+    sensor_reader.set_front_left_absolute_pwm(
+        std::make_unique<frc::DigitalInput>(1));
+
+    sensor_reader.set_front_right_encoder(make_encoder(0));
+    sensor_reader.set_front_right_absolute_pwm(
+        std::make_unique<frc::DigitalInput>(0));
+
+    sensor_reader.set_back_left_encoder(make_encoder(2));
+    sensor_reader.set_back_left_absolute_pwm(
+        std::make_unique<frc::DigitalInput>(2));
+
+    sensor_reader.set_back_right_encoder(make_encoder(3));
+    sensor_reader.set_back_right_absolute_pwm(
+        std::make_unique<frc::DigitalInput>(3));
+
+    AddLoop(&sensor_reader_event_loop);
+
+    RunLoops();
+  }
+};
+
+}  // namespace wpilib
+}  // namespace y2023_bot4
+
+AOS_ROBOT_CLASS(::y2023_bot4::wpilib::WPILibRobot)
diff --git a/y2023_bot4/y2023_bot4.json b/y2023_bot4/y2023_bot4.json
new file mode 100644
index 0000000..49db6fc
--- /dev/null
+++ b/y2023_bot4/y2023_bot4.json
@@ -0,0 +1,19 @@
+{
+  "channel_storage_duration": 10000000000,
+  "maps": [
+    {
+      "match": {
+        "name": "/aos",
+        "type": "aos.RobotState"
+      },
+      "rename": {
+        "name": "/roborio/aos"
+      }
+    }
+  ],
+  "imports": [
+    "y2023_bot4_roborio.json",
+    "y2023_bot4_imu.json",
+    "y2023_bot4_logger.json"
+  ]
+}
diff --git a/y2023_bot4/y2023_bot4_imu.json b/y2023_bot4/y2023_bot4_imu.json
new file mode 100644
index 0000000..274b158
--- /dev/null
+++ b/y2023_bot4/y2023_bot4_imu.json
@@ -0,0 +1,212 @@
+{
+  "channels": [
+    {
+      "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",
+      "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",
+        "logger"
+      ],
+      "max_size": 400,
+      "destination_nodes": [
+        {
+          "name": "roborio",
+          "priority": 1,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "imu"
+          ],
+          "time_to_live": 5000000
+        },
+        {
+          "name": "logger",
+          "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": "/imu/aos/remote_timestamps/logger/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
+    }
+  ],
+  "applications": [
+    {
+      "name": "message_bridge_client",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "imu",
+      "executable_name": "imu_main",
+      "user": "pi",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "message_bridge_server",
+      "executable_name": "message_bridge_server",
+      "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"
+      ]
+    }
+  ],
+  "maps": [
+    {
+      "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": "logger"
+    },
+    {
+      "name": "roborio"
+    }
+  ]
+}
diff --git a/y2023_bot4/y2023_bot4_logger.json b/y2023_bot4/y2023_bot4_logger.json
new file mode 100644
index 0000000..5cca31f
--- /dev/null
+++ b/y2023_bot4/y2023_bot4_logger.json
@@ -0,0 +1,190 @@
+{
+  "channels": [
+    {
+      "name": "/roborio/aos",
+      "type": "aos.message_bridge.Timestamp",
+      "source_node": "roborio",
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "logger"
+      ],
+      "destination_nodes": [
+        {
+          "name": "logger",
+          "priority": 1,
+          "time_to_live": 5000000,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "roborio"
+          ]
+        }
+      ]
+    },
+    {
+      "name": "/logger/aos",
+      "type": "aos.timing.Report",
+      "source_node": "logger",
+      "frequency": 50,
+      "num_senders": 20,
+      "max_size": 4096
+    },
+    {
+      "name": "/logger/aos",
+      "type": "aos.logging.LogMessageFbs",
+      "source_node": "logger",
+      "frequency": 400,
+      "num_senders": 20
+    },
+    {
+      "name": "/logger/aos",
+      "type": "aos.message_bridge.ServerStatistics",
+      "source_node": "logger",
+      "frequency": 10,
+      "num_senders": 2
+    },
+    {
+      "name": "/logger/aos",
+      "type": "aos.message_bridge.ClientStatistics",
+      "source_node": "logger",
+      "frequency": 20,
+      "max_size": 2000,
+      "num_senders": 2
+    },
+    {
+      "name": "/logger/aos",
+      "type": "aos.logging.DynamicLogCommand",
+      "source_node": "logger",
+      "frequency": 10,
+      "num_senders": 2
+    },
+    {
+      "name": "/logger/aos",
+      "type": "aos.starter.Status",
+      "source_node": "logger",
+      "frequency": 50,
+      "num_senders": 20,
+      "max_size": 2000
+    },
+    {
+      "name": "/logger/aos",
+      "type": "aos.starter.StarterRpc",
+      "source_node": "logger",
+      "frequency": 10,
+      "num_senders": 2
+    },
+    {
+      "name": "/logger/aos",
+      "type": "aos.message_bridge.Timestamp",
+      "source_node": "logger",
+      "frequency": 15,
+      "num_senders": 2,
+      "max_size": 400,
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "imu",
+        "roborio"
+      ],
+      "destination_nodes": [
+        {
+          "name": "imu",
+          "priority": 1,
+          "time_to_live": 5000000,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "logger"
+          ]
+        },
+        {
+          "name": "roborio",
+          "priority": 1,
+          "time_to_live": 5000000,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "logger"
+          ]
+        }
+      ]
+    },
+    {
+      "name": "/logger/aos/remote_timestamps/imu/logger/aos/aos-message_bridge-Timestamp",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "logger",
+      "logger": "NOT_LOGGED",
+      "frequency": 20,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
+      "name": "/logger/aos/remote_timestamps/roborio/logger/aos/aos-message_bridge-Timestamp",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "logger",
+      "logger": "NOT_LOGGED",
+      "frequency": 20,
+      "num_senders": 2,
+      "max_size": 200
+    }
+  ],
+    "maps": [
+    {
+      "match": {
+        "name": "/aos*",
+        "source_node": "logger"
+      },
+      "rename": {
+        "name": "/logger/aos"
+      }
+    },
+    {
+      "match": {
+        "name": "/constants*",
+        "source_node": "logger"
+      },
+      "rename": {
+        "name": "/logger/constants"
+      }
+    },
+    {
+      "match": {
+        "name": "/camera*",
+        "source_node": "logger"
+      },
+      "rename": {
+        "name": "/logger/camera"
+      }
+    }
+  ],
+  "applications": [
+    {
+      "name": "message_bridge_client",
+      "nodes": [
+        "logger"
+      ]
+    },
+    {
+      "name": "message_bridge_server",
+      "executable_name": "message_bridge_server",
+      "user": "pi",
+      "nodes": [
+        "logger"
+      ]
+    }
+  ],
+  "nodes": [
+    {
+      "name": "logger",
+      "hostname": "pi5",
+      "hostnames": [
+        "pi-971-5",
+        "pi-9971-5",
+        "pi-7971-5"
+      ],
+      "port": 9971
+    },
+    {
+      "name": "imu"
+    },
+    {
+      "name": "roborio"
+    }
+    ]
+}
diff --git a/y2023_bot4/y2023_bot4_roborio.json b/y2023_bot4/y2023_bot4_roborio.json
new file mode 100644
index 0000000..7ff175c
--- /dev/null
+++ b/y2023_bot4/y2023_bot4_roborio.json
@@ -0,0 +1,350 @@
+{
+    "channels": [
+        {
+            "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",
+            "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/remote_timestamps/logger/roborio/aos/aos-message_bridge-Timestamp",
+            "type": "aos.message_bridge.RemoteMessage",
+            "frequency": 300,
+            "source_node": "roborio"
+        },
+        {
+            "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": "/drivetrain",
+            "type": "y2023_bot4.AbsoluteDrivetrainPosition",
+            "source_node": "roborio",
+            "frequency": 250,
+            "num_senders": 1,
+            "max_size": 480
+        },
+        {
+            "name": "/drivetrain",
+            "type": "y2023_bot4.AbsoluteCANPosition",
+            "source_node": "roborio",
+            "frequency": 250,
+            "num_senders": 1,
+            "max_size": 480
+        },
+        {
+            "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.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.swerve.Position",
+            "source_node": "roborio",
+            "frequency": 400,
+            "max_size": 112,
+            "num_senders": 2
+        },
+        {
+            "name": "/drivetrain",
+            "type": "frc971.control_loops.drivetrain.swerve.Output",
+            "source_node": "roborio",
+            "frequency": 400,
+            "max_size": 200,
+            "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": "wpilib_interface",
+            "executable_name": "wpilib_interface",
+            "args": [
+                "--nodie_on_malloc",
+                "--ctre_diag_server"
+            ],
+            "nodes": [
+                "roborio"
+            ]
+        },
+        {
+            "name": "swerve_publisher",
+            "executable_name": "swerve_publisher",
+            "autostart": false,
+            "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-9971-FRC"
+            ],
+            "port": 9971
+        },
+        {
+            "name": "imu"
+        },
+        {
+            "name": "logger"
+        }
+    ]
+}