Add y2022_bot3 folder

remove unnecessary files from y2022 for the 3rd robot

Change-Id: I79ba255b5167782530741626281f1eb5642c952a
Signed-off-by: Henry Speiser <henry@speiser.net>
diff --git a/y2022_bot3/BUILD b/y2022_bot3/BUILD
new file mode 100644
index 0000000..8af6882
--- /dev/null
+++ b/y2022_bot3/BUILD
@@ -0,0 +1,209 @@
+load("//frc971:downloader.bzl", "robot_downloader")
+load("//aos:config.bzl", "aos_config")
+
+robot_downloader(
+    binaries = [
+        "//aos/network:web_proxy_main",
+        "//aos/events/logging:log_cat",
+    ],
+    data = [
+        ":aos_config",
+        "@ctre_phoenix_api_cpp_athena//:shared_libraries",
+        "@ctre_phoenix_cci_athena//:shared_libraries",
+    ],
+    dirs = [
+        "//y2022_bot3/actors:splines",
+    ],
+    start_binaries = [
+        "//aos/events/logging:logger_main",
+        "//aos/network:web_proxy_main",
+        ":joystick_reader",
+        ":wpilib_interface",
+        "//aos/network:message_bridge_client",
+        "//aos/network:message_bridge_server",
+        "//y2022_bot3/actors:binaries",
+        "//y2022_bot3/control_loops/drivetrain:drivetrain",
+        "//y2022_bot3/control_loops/drivetrain:trajectory_generator",
+        "//y2022_bot3/control_loops/superstructure:superstructure",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+)
+
+robot_downloader(
+    name = "pi_download",
+    binaries = [
+        "//aos/events/logging:log_cat",
+    ],
+    data = [
+        ":aos_config",
+    ],
+    start_binaries = [
+        "//aos/events/logging:logger_main",
+        "//aos/network:message_bridge_client",
+        "//aos/network:message_bridge_server",
+        "//aos/network:web_proxy_main",
+    ],
+    target_compatible_with = ["//tools/platforms/hardware:raspberry_pi"],
+    target_type = "pi",
+)
+
+aos_config(
+    name = "aos_config",
+    src = "y2022_bot3.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 = "y2022_bot3_imu.json",
+    flatbuffers = [
+        "//aos/network:message_bridge_client_fbs",
+        "//aos/network:message_bridge_server_fbs",
+        "//aos/network:timestamp_fbs",
+        "//aos/network:remote_message_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 = "y2022_bot3_roborio.json",
+    flatbuffers = [
+        "//aos/network:remote_message_fbs",
+        "//aos/network:message_bridge_client_fbs",
+        "//aos/network:message_bridge_server_fbs",
+        "//aos/network:timestamp_fbs",
+        "//y2019/control_loops/drivetrain:target_selector_fbs",
+        "//y2022_bot3/control_loops/superstructure:superstructure_goal_fbs",
+        "//y2022_bot3/control_loops/superstructure:superstructure_output_fbs",
+        "//y2022_bot3/control_loops/superstructure:superstructure_position_fbs",
+        "//y2022_bot3/control_loops/superstructure:superstructure_status_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",
+        "//y2022_bot3/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/events:shm_event_loop",
+        "//aos/logging",
+        "//aos/stl_mutex",
+        "//aos/time",
+        "//aos/util:log_interval",
+        "//aos/util:phased_loop",
+        "//aos/util:wrapping_counter",
+        "//frc971/autonomous:auto_mode_fbs",
+        "//frc971/control_loops:control_loop",
+        "//frc971/control_loops:control_loops_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:drivetrain_writer",
+        "//frc971/wpilib:encoder_and_potentiometer",
+        "//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:wpilib",
+        "//y2022_bot3/control_loops/superstructure:superstructure_output_fbs",
+        "//y2022_bot3/control_loops/superstructure:superstructure_position_fbs",
+    ],
+)
+
+cc_binary(
+    name = "joystick_reader",
+    srcs = [
+        ":joystick_reader.cc",
+    ],
+    deps = [
+        ":constants",
+        "//aos:init",
+        "//aos/actions:action_lib",
+        "//aos/logging",
+        "//frc971/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",
+        "//y2022_bot3/control_loops/drivetrain:drivetrain_base",
+        "//y2022_bot3/control_loops/superstructure:superstructure_goal_fbs",
+        "//y2022_bot3/control_loops/superstructure:superstructure_status_fbs",
+    ],
+)
+
+py_library(
+    name = "python_init",
+    srcs = ["__init__.py"],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+)
+
+sh_binary(
+    name = "log_web_proxy",
+    srcs = ["log_web_proxy.sh"],
+    data = [
+        ":aos_config",
+        "//aos/network:log_web_proxy_main",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+)
diff --git a/y2022_bot3/__init__.py b/y2022_bot3/__init__.py
new file mode 100644
index 0000000..e69de29
--- /dev/null
+++ b/y2022_bot3/__init__.py
diff --git a/y2022_bot3/actors/BUILD b/y2022_bot3/actors/BUILD
new file mode 100644
index 0000000..783894f
--- /dev/null
+++ b/y2022_bot3/actors/BUILD
@@ -0,0 +1,74 @@
+load("//frc971/downloader:downloader.bzl", "aos_downloader_dir")
+
+filegroup(
+    name = "binaries.stripped",
+    srcs = [
+        ":autonomous_action.stripped",
+    ],
+    visibility = ["//visibility:public"],
+)
+
+filegroup(
+    name = "binaries",
+    srcs = [
+        ":autonomous_action",
+    ],
+    visibility = ["//visibility:public"],
+)
+
+filegroup(
+    name = "spline_jsons",
+    srcs = glob([
+        "splines/*.json",
+    ]),
+    visibility = ["//visibility:public"],
+)
+
+aos_downloader_dir(
+    name = "splines",
+    srcs = [
+        ":spline_jsons",
+    ],
+    dir = "splines",
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+)
+
+cc_library(
+    name = "autonomous_action_lib",
+    srcs = [
+        "auto_splines.cc",
+        "autonomous_actor.cc",
+    ],
+    hdrs = [
+        "auto_splines.h",
+        "autonomous_actor.h",
+    ],
+    deps = [
+        "//aos/events:event_loop",
+        "//aos/logging",
+        "//aos/util:phased_loop",
+        "//frc971/autonomous:base_autonomous_actor",
+        "//frc971/control_loops:control_loops_fbs",
+        "//frc971/control_loops:profiled_subsystem_fbs",
+        "//frc971/control_loops/drivetrain:drivetrain_config",
+        "//frc971/control_loops/drivetrain:localizer_fbs",
+        "//y2022_bot3:constants",
+        "//y2022_bot3/control_loops/drivetrain:drivetrain_base",
+        "//y2022_bot3/control_loops/superstructure:superstructure_goal_fbs",
+        "//y2022_bot3/control_loops/superstructure:superstructure_status_fbs",
+    ],
+)
+
+cc_binary(
+    name = "autonomous_action",
+    srcs = [
+        "autonomous_actor_main.cc",
+    ],
+    deps = [
+        ":autonomous_action_lib",
+        "//aos:init",
+        "//aos/events:shm_event_loop",
+        "//frc971/autonomous:auto_fbs",
+    ],
+)
diff --git a/y2022_bot3/actors/auto_splines.cc b/y2022_bot3/actors/auto_splines.cc
new file mode 100644
index 0000000..047eac8
--- /dev/null
+++ b/y2022_bot3/actors/auto_splines.cc
@@ -0,0 +1,54 @@
+#include "y2022_bot3/actors/auto_splines.h"
+
+#include "frc971/control_loops/control_loops_generated.h"
+
+namespace y2022_bot3 {
+namespace actors {
+
+void MaybeFlipSpline(
+    aos::Sender<frc971::control_loops::drivetrain::Goal>::Builder *builder,
+    flatbuffers::Offset<flatbuffers::Vector<float>> spline_y_offset,
+    bool is_left) {
+  flatbuffers::Vector<float> *spline_y =
+      GetMutableTemporaryPointer(*builder->fbb(), spline_y_offset);
+
+  if (!is_left) {
+    for (size_t i = 0; i < spline_y->size(); i++) {
+      spline_y->Mutate(i, -spline_y->Get(i));
+    }
+  }
+}
+
+flatbuffers::Offset<frc971::MultiSpline> FixSpline(
+    aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+        *builder,
+    flatbuffers::Offset<frc971::MultiSpline> spline_offset,
+    aos::Alliance alliance) {
+  frc971::MultiSpline *spline =
+      GetMutableTemporaryPointer(*builder->fbb(), spline_offset);
+  flatbuffers::Vector<float> *spline_x = spline->mutable_spline_x();
+  flatbuffers::Vector<float> *spline_y = spline->mutable_spline_y();
+
+  if (alliance == aos::Alliance::kBlue) {
+    for (size_t ii = 0; ii < spline_x->size(); ++ii) {
+      spline_x->Mutate(ii, -spline_x->Get(ii));
+    }
+    for (size_t ii = 0; ii < spline_y->size(); ++ii) {
+      spline_y->Mutate(ii, -spline_y->Get(ii));
+    }
+  }
+  return spline_offset;
+}
+
+flatbuffers::Offset<frc971::MultiSpline> AutonomousSplines::TestSpline(
+    aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+        *builder,
+    aos::Alliance alliance) {
+  return FixSpline(
+      builder,
+      aos::CopyFlatBuffer<frc971::MultiSpline>(test_spline_, builder->fbb()),
+      alliance);
+}
+
+}  // namespace actors
+}  // namespace y2022_bot3
diff --git a/y2022_bot3/actors/auto_splines.h b/y2022_bot3/actors/auto_splines.h
new file mode 100644
index 0000000..c4c32fb
--- /dev/null
+++ b/y2022_bot3/actors/auto_splines.h
@@ -0,0 +1,42 @@
+#ifndef Y2022_BOT3_ACTORS_AUTO_SPLINES_H_
+#define Y2022_BOT3_ACTORS_AUTO_SPLINES_H_
+
+#include "aos/events/event_loop.h"
+#include "aos/flatbuffer_merge.h"
+#include "frc971/control_loops/control_loops_generated.h"
+#include "frc971/control_loops/drivetrain/drivetrain_goal_generated.h"
+#include "frc971/input/joystick_state_generated.h"
+/*
+
+  The cooridinate system for the autonomous splines is the same as the spline
+  python generator and drivetrain spline systems.
+
+*/
+
+namespace y2022_bot3 {
+namespace actors {
+
+class AutonomousSplines {
+ public:
+  AutonomousSplines()
+      : test_spline_(aos::JsonFileToFlatbuffer<frc971::MultiSpline>(
+            "splines/test_spline.json")) {}
+
+  static flatbuffers::Offset<frc971::MultiSpline> BasicSSpline(
+      aos::Sender<frc971::control_loops::drivetrain::Goal>::Builder *builder);
+  static flatbuffers::Offset<frc971::MultiSpline> StraightLine(
+      aos::Sender<frc971::control_loops::drivetrain::Goal>::Builder *builder);
+
+  flatbuffers::Offset<frc971::MultiSpline> TestSpline(
+      aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+          *builder,
+      aos::Alliance alliance);
+
+ private:
+  aos::FlatbufferDetachedBuffer<frc971::MultiSpline> test_spline_;
+};
+
+}  // namespace actors
+}  // namespace y2022_bot3
+
+#endif  // Y2022_BOT3_ACTORS_AUTO_SPLINES_H_
diff --git a/y2022_bot3/actors/autonomous_actor.cc b/y2022_bot3/actors/autonomous_actor.cc
new file mode 100644
index 0000000..814921d
--- /dev/null
+++ b/y2022_bot3/actors/autonomous_actor.cc
@@ -0,0 +1,185 @@
+#include "y2022_bot3/actors/autonomous_actor.h"
+
+#include <chrono>
+#include <cinttypes>
+#include <cmath>
+
+#include "aos/logging/logging.h"
+#include "aos/network/team_number.h"
+#include "aos/util/math.h"
+#include "frc971/control_loops/drivetrain/localizer_generated.h"
+#include "y2022_bot3/actors/auto_splines.h"
+#include "y2022_bot3/constants.h"
+#include "y2022_bot3/control_loops/drivetrain/drivetrain_base.h"
+
+DEFINE_bool(spline_auto, false, "If true, define a spline autonomous mode");
+
+namespace y2022_bot3 {
+namespace actors {
+
+using ::aos::monotonic_clock;
+using frc971::CreateProfileParameters;
+using ::frc971::ProfileParametersT;
+using frc971::control_loops::CreateStaticZeroingSingleDOFProfiledSubsystemGoal;
+using frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal;
+using frc971::control_loops::drivetrain::LocalizerControl;
+
+namespace chrono = ::std::chrono;
+
+AutonomousActor::AutonomousActor(::aos::EventLoop *event_loop)
+    : frc971::autonomous::BaseAutonomousActor(
+          event_loop, control_loops::drivetrain::GetDrivetrainConfig()),
+      localizer_control_sender_(
+          event_loop->MakeSender<
+              ::frc971::control_loops::drivetrain::LocalizerControl>(
+              "/drivetrain")),
+      superstructure_goal_sender_(
+          event_loop->MakeSender<control_loops::superstructure::Goal>(
+              "/superstructure")),
+      superstructure_status_fetcher_(
+          event_loop->MakeFetcher<control_loops::superstructure::Status>(
+              "/superstructure")),
+      joystick_state_fetcher_(
+          event_loop->MakeFetcher<aos::JoystickState>("/aos")),
+      robot_state_fetcher_(event_loop->MakeFetcher<aos::RobotState>("/aos")),
+      auto_splines_() {
+  set_max_drivetrain_voltage(12.0);
+  replan_timer_ = event_loop->AddTimer([this]() { Replan(); });
+  event_loop->OnRun([this, event_loop]() {
+    replan_timer_->Setup(event_loop->monotonic_now());
+    button_poll_->Setup(event_loop->monotonic_now(), chrono::milliseconds(50));
+  });
+
+  button_poll_ = event_loop->AddTimer([this]() {
+    const aos::monotonic_clock::time_point now =
+        this->event_loop()->context().monotonic_event_time;
+    if (robot_state_fetcher_.Fetch()) {
+      if (robot_state_fetcher_->user_button()) {
+        user_indicated_safe_to_reset_ = true;
+        MaybeSendStartingPosition();
+      }
+    }
+    if (joystick_state_fetcher_.Fetch()) {
+      if (joystick_state_fetcher_->has_alliance() &&
+          (joystick_state_fetcher_->alliance() != alliance_)) {
+        alliance_ = joystick_state_fetcher_->alliance();
+        is_planned_ = false;
+        // Only kick the planning out by 2 seconds. If we end up enabled in that
+        // second, then we will kick it out further based on the code below.
+        replan_timer_->Setup(now + std::chrono::seconds(2));
+      }
+      if (joystick_state_fetcher_->enabled()) {
+        if (!is_planned_) {
+          // Only replan once we've been disabled for 5 seconds.
+          replan_timer_->Setup(now + std::chrono::seconds(5));
+        }
+      }
+    }
+  });
+}
+
+void AutonomousActor::Replan() {
+  LOG(INFO) << "Alliance " << static_cast<int>(alliance_);
+  if (alliance_ == aos::Alliance::kInvalid) {
+    return;
+  }
+  sent_starting_position_ = false;
+  if (FLAGS_spline_auto) {
+    test_spline_ =
+        PlanSpline(std::bind(&AutonomousSplines::TestSpline, &auto_splines_,
+                             std::placeholders::_1, alliance_),
+                   SplineDirection::kForward);
+
+    starting_position_ = test_spline_->starting_position();
+  }
+
+  is_planned_ = true;
+
+  MaybeSendStartingPosition();
+}
+
+void AutonomousActor::MaybeSendStartingPosition() {
+  if (is_planned_ && user_indicated_safe_to_reset_ &&
+      !sent_starting_position_) {
+    CHECK(starting_position_);
+    SendStartingPosition(starting_position_.value());
+  }
+}
+
+void AutonomousActor::Reset() {
+  InitializeEncoders();
+  ResetDrivetrain();
+
+  joystick_state_fetcher_.Fetch();
+  CHECK(joystick_state_fetcher_.get() != nullptr)
+      << "Expect at least one JoystickState message before running auto...";
+  alliance_ = joystick_state_fetcher_->alliance();
+}
+
+bool AutonomousActor::RunAction(
+    const ::frc971::autonomous::AutonomousActionParams *params) {
+  Reset();
+  if (!user_indicated_safe_to_reset_) {
+    AOS_LOG(WARNING, "Didn't send starting position prior to starting auto.");
+    CHECK(starting_position_);
+    SendStartingPosition(starting_position_.value());
+  }
+  // Clear this so that we don't accidentally resend things as soon as we replan
+  // later.
+  user_indicated_safe_to_reset_ = false;
+  is_planned_ = false;
+  starting_position_.reset();
+
+  AOS_LOG(INFO, "Params are %d\n", params->mode());
+  if (alliance_ == aos::Alliance::kInvalid) {
+    AOS_LOG(INFO, "Aborting autonomous due to invalid alliance selection.");
+    return false;
+  }
+  if (FLAGS_spline_auto) {
+    SplineAuto();
+  }
+
+  return true;
+}
+
+void AutonomousActor::SendStartingPosition(const Eigen::Vector3d &start) {
+  // Set up the starting position for the blue alliance.
+
+  // TODO(james): Resetting the localizer breaks the left/right statespace
+  // controller.  That is a bug, but we can fix that later by not resetting.
+  auto builder = localizer_control_sender_.MakeBuilder();
+
+  LocalizerControl::Builder localizer_control_builder =
+      builder.MakeBuilder<LocalizerControl>();
+  localizer_control_builder.add_x(start(0));
+  localizer_control_builder.add_y(start(1));
+  localizer_control_builder.add_theta(start(2));
+  localizer_control_builder.add_theta_uncertainty(0.00001);
+  LOG(INFO) << "User button pressed, x: " << start(0) << " y: " << start(1)
+            << " theta: " << start(2);
+  if (builder.Send(localizer_control_builder.Finish()) !=
+      aos::RawSender::Error::kOk) {
+    AOS_LOG(ERROR, "Failed to reset localizer.\n");
+  }
+}
+
+void AutonomousActor::SplineAuto() {
+  CHECK(test_spline_);
+
+  if (!test_spline_->WaitForPlan()) return;
+  test_spline_->Start();
+
+  if (!test_spline_->WaitForSplineDistanceRemaining(0.02)) return;
+}
+
+void AutonomousActor::SendSuperstructureGoal() {
+  auto builder = superstructure_goal_sender_.MakeBuilder();
+  superstructure::Goal::Builder superstructure_builder = builder.MakeBuilder<superstructure::Goal>();
+  if (builder.Send(superstructure_builder.Finish()) !=
+      aos::RawSender::Error::kOk) {
+    AOS_LOG(ERROR, "Sending superstructure goal failed.\n");
+  }
+}
+
+}  // namespace actors
+}  // namespace y2022_bot3
diff --git a/y2022_bot3/actors/autonomous_actor.h b/y2022_bot3/actors/autonomous_actor.h
new file mode 100644
index 0000000..72262fb
--- /dev/null
+++ b/y2022_bot3/actors/autonomous_actor.h
@@ -0,0 +1,66 @@
+#ifndef Y2022_BOT3_ACTORS_AUTONOMOUS_ACTOR_H_
+#define Y2022_BOT3_ACTORS_AUTONOMOUS_ACTOR_H_
+
+#include "aos/actions/actions.h"
+#include "aos/actions/actor.h"
+#include "frc971/autonomous/base_autonomous_actor.h"
+#include "frc971/control_loops/control_loops_generated.h"
+#include "frc971/control_loops/drivetrain/drivetrain_config.h"
+#include "frc971/control_loops/drivetrain/localizer_generated.h"
+#include "y2022_bot3/actors/auto_splines.h"
+#include "y2022_bot3/control_loops/superstructure/superstructure_goal_generated.h"
+#include "y2022_bot3/control_loops/superstructure/superstructure_status_generated.h"
+
+namespace y2022_bot3 {
+namespace actors {
+
+using frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal;
+
+namespace superstructure = y2022_bot3::control_loops::superstructure;
+
+class AutonomousActor : public ::frc971::autonomous::BaseAutonomousActor {
+ public:
+  explicit AutonomousActor(::aos::EventLoop *event_loop);
+
+  bool RunAction(
+      const ::frc971::autonomous::AutonomousActionParams *params) override;
+
+ private:
+  void Reset();
+
+  void SendSuperstructureGoal();
+  void SendStartingPosition(const Eigen::Vector3d &start);
+  void MaybeSendStartingPosition();
+
+  void SplineAuto();
+
+  void Replan();
+
+  aos::Sender<frc971::control_loops::drivetrain::LocalizerControl>
+      localizer_control_sender_;
+  aos::Sender<y2022_bot3::control_loops::superstructure::Goal>
+      superstructure_goal_sender_;
+  aos::Fetcher<y2022_bot3::control_loops::superstructure::Status>
+      superstructure_status_fetcher_;
+  aos::Fetcher<aos::JoystickState> joystick_state_fetcher_;
+  aos::Fetcher<aos::RobotState> robot_state_fetcher_;
+
+  aos::TimerHandler *replan_timer_;
+  aos::TimerHandler *button_poll_;
+
+  std::optional<SplineHandle> test_spline_;
+
+  aos::Alliance alliance_ = aos::Alliance::kInvalid;
+  AutonomousSplines auto_splines_;
+  bool user_indicated_safe_to_reset_ = false;
+  bool sent_starting_position_ = false;
+
+  bool is_planned_ = false;
+
+  std::optional<Eigen::Vector3d> starting_position_;
+};
+
+}  // namespace actors
+}  // namespace y2022_bot3
+
+#endif  // Y2022_BOT3_ACTORS_AUTONOMOUS_ACTOR_H_
diff --git a/y2022_bot3/actors/autonomous_actor_main.cc b/y2022_bot3/actors/autonomous_actor_main.cc
new file mode 100644
index 0000000..b336867
--- /dev/null
+++ b/y2022_bot3/actors/autonomous_actor_main.cc
@@ -0,0 +1,19 @@
+#include <cstdio>
+
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "y2022_bot3/actors/autonomous_actor.h"
+
+int main(int argc, char *argv[]) {
+  ::aos::InitGoogle(&argc, &argv);
+
+  aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+      aos::configuration::ReadConfig("aos_config.json");
+
+  ::aos::ShmEventLoop event_loop(&config.message());
+  ::y2022_bot3::actors::AutonomousActor autonomous(&event_loop);
+
+  event_loop.Run();
+
+  return 0;
+}
diff --git a/y2022_bot3/actors/splines/README.md b/y2022_bot3/actors/splines/README.md
new file mode 100644
index 0000000..c655416
--- /dev/null
+++ b/y2022_bot3/actors/splines/README.md
@@ -0,0 +1,3 @@
+# Spline Descriptions
+This folder contains reference material for what each spline does
+
diff --git a/y2022_bot3/actors/splines/test_spline.json b/y2022_bot3/actors/splines/test_spline.json
new file mode 100644
index 0000000..733d516
--- /dev/null
+++ b/y2022_bot3/actors/splines/test_spline.json
@@ -0,0 +1 @@
+{"spline_count": 1, "spline_x": [0, 0.4, 0.4, 0.6, 0.6, 1.0], "spline_y": [0, 0, 0.05, 0.1, 0.15, 0.15], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 1}, {"constraint_type": "LATERAL_ACCELERATION", "value": 1}, {"constraint_type": "VOLTAGE", "value": 2}]}
diff --git a/y2022_bot3/constants.cc b/y2022_bot3/constants.cc
new file mode 100644
index 0000000..84e6a0d
--- /dev/null
+++ b/y2022_bot3/constants.cc
@@ -0,0 +1,57 @@
+#include "y2022_bot3/constants.h"
+
+#include <cinttypes>
+#include <map>
+
+#if __has_feature(address_sanitizer)
+#include "sanitizer/lsan_interface.h"
+#endif
+
+#include "absl/base/call_once.h"
+#include "aos/mutex/mutex.h"
+#include "aos/network/team_number.h"
+#include "glog/logging.h"
+
+namespace y2022_bot3 {
+namespace constants {
+
+const int Values::kZeroingSampleSize;
+
+namespace {
+
+const uint16_t kCompTeamNumber = 971;
+const uint16_t kPracticeTeamNumber = 9971;
+const uint16_t kCodingRobotTeamNumber = 7971;
+
+}  // namespace
+
+Values MakeValues(uint16_t team) {
+  LOG(INFO) << "creating a Constants for team: " << team;
+
+  Values r;
+
+  switch (team) {
+    // A set of constants for tests.
+    case 1:
+      break;
+
+    case kCompTeamNumber:
+      break;
+
+    case kPracticeTeamNumber:
+      break;
+
+    case kCodingRobotTeamNumber:
+      break;
+
+    default:
+      LOG(FATAL) << "unknown team: " << team;
+  }
+
+  return r;
+}
+
+Values MakeValues() { return MakeValues(aos::network::GetTeamNumber()); }
+
+}  // namespace constants
+}  // namespace y2022_bot3
diff --git a/y2022_bot3/constants.h b/y2022_bot3/constants.h
new file mode 100644
index 0000000..877cff5
--- /dev/null
+++ b/y2022_bot3/constants.h
@@ -0,0 +1,59 @@
+#ifndef Y2022_BOT3_CONSTANTS_H_
+#define Y2022_BOT3_CONSTANTS_H_
+
+#include <array>
+#include <cmath>
+#include <cstdint>
+
+#include "frc971/constants.h"
+#include "frc971/control_loops/pose.h"
+#include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h"
+#include "frc971/shooter_interpolation/interpolation.h"
+#include "y2022_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+
+using ::frc971::shooter_interpolation::InterpolationTable;
+
+namespace y2022_bot3 {
+namespace constants {
+
+struct Values {
+  static const int kZeroingSampleSize = 200;
+
+  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 double DrivetrainEncoderToMeters(int32_t in) {
+    return ((static_cast<double>(in) /
+             kDrivetrainEncoderCountsPerRevolution()) *
+            (2.0 * M_PI)) *
+           kDrivetrainEncoderRatio() * control_loops::drivetrain::kWheelRadius;
+  }
+
+  struct PotAndAbsEncoderConstants {
+    ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemParams<
+        ::frc971::zeroing::PotAndAbsoluteEncoderZeroingEstimator>
+        subsystem_params;
+    double potentiometer_offset;
+  };
+};
+// Creates and returns a Values instance for the constants.
+// Should be called before realtime because this allocates memory.
+// Only the first call to either of these will be used.
+Values MakeValues(uint16_t team);
+
+// Calls MakeValues with aos::network::GetTeamNumber()
+Values MakeValues();
+
+}  // namespace constants
+}  // namespace y2022_bot3
+
+#endif  // Y2022_CONSTANTS_H_
diff --git a/y2022_bot3/control_loops/BUILD b/y2022_bot3/control_loops/BUILD
new file mode 100644
index 0000000..530281f
--- /dev/null
+++ b/y2022_bot3/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 = ["//y2022_bot3:python_init"],
+)
diff --git a/y2022_bot3/control_loops/__init__.py b/y2022_bot3/control_loops/__init__.py
new file mode 100644
index 0000000..e69de29
--- /dev/null
+++ b/y2022_bot3/control_loops/__init__.py
diff --git a/y2022_bot3/control_loops/drivetrain/BUILD b/y2022_bot3/control_loops/drivetrain/BUILD
new file mode 100644
index 0000000..ecdcf6b
--- /dev/null
+++ b/y2022_bot3/control_loops/drivetrain/BUILD
@@ -0,0 +1,113 @@
+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 //y2022_bot3/control_loops/python:drivetrain) $(OUTS)",
+    target_compatible_with = ["@platforms//os:linux"],
+    tools = [
+        "//y2022_bot3/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 //y2022_bot3/control_loops/python:polydrivetrain) $(OUTS)",
+    target_compatible_with = ["@platforms//os:linux"],
+    tools = [
+        "//y2022_bot3/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",
+    ],
+)
+
+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",
+        "//y2022_bot3:aos_config",
+    ],
+)
+
+cc_binary(
+    name = "trajectory_generator",
+    srcs = [
+        "trajectory_generator_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:trajectory_generator",
+    ],
+)
diff --git a/y2022_bot3/control_loops/drivetrain/drivetrain_base.cc b/y2022_bot3/control_loops/drivetrain/drivetrain_base.cc
new file mode 100644
index 0000000..a97e0dd
--- /dev/null
+++ b/y2022_bot3/control_loops/drivetrain/drivetrain_base.cc
@@ -0,0 +1,71 @@
+#include "y2022_bot3/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 "y2022_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+#include "y2022_bot3/control_loops/drivetrain/hybrid_velocity_drivetrain.h"
+#include "y2022_bot3/control_loops/drivetrain/kalman_drivetrain_motor_plant.h"
+#include "y2022_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
+
+using ::frc971::control_loops::drivetrain::DownEstimatorConfig;
+using ::frc971::control_loops::drivetrain::DrivetrainConfig;
+
+namespace chrono = ::std::chrono;
+
+namespace y2022_bot3 {
+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 */,
+      true /*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}};
+
+  return kDrivetrainConfig;
+};
+
+}  // namespace drivetrain
+}  // namespace control_loops
+}  // namespace y2022_bot3
diff --git a/y2022_bot3/control_loops/drivetrain/drivetrain_base.h b/y2022_bot3/control_loops/drivetrain/drivetrain_base.h
new file mode 100644
index 0000000..cce197e
--- /dev/null
+++ b/y2022_bot3/control_loops/drivetrain/drivetrain_base.h
@@ -0,0 +1,17 @@
+#ifndef Y2022_BOT3_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
+#define Y2022_BOT3_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
+
+#include "frc971/control_loops/drivetrain/drivetrain_config.h"
+
+namespace y2022_bot3 {
+namespace control_loops {
+namespace drivetrain {
+
+const ::frc971::control_loops::drivetrain::DrivetrainConfig<double>
+    &GetDrivetrainConfig();
+
+}  // namespace drivetrain
+}  // namespace control_loops
+}  // namespace y2022_bot3
+
+#endif  // Y2022_BOT3_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
diff --git a/y2022_bot3/control_loops/drivetrain/drivetrain_main.cc b/y2022_bot3/control_loops/drivetrain/drivetrain_main.cc
new file mode 100644
index 0000000..fda7119
--- /dev/null
+++ b/y2022_bot3/control_loops/drivetrain/drivetrain_main.cc
@@ -0,0 +1,25 @@
+#include <memory>
+
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "frc971/control_loops/drivetrain/drivetrain.h"
+#include "y2022_bot3/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::DeadReckonEkf>
+      localizer =
+          std::make_unique<::frc971::control_loops::drivetrain::DeadReckonEkf>(
+              &event_loop,
+              ::y2022_bot3::control_loops::drivetrain::GetDrivetrainConfig());
+  event_loop.Run();
+
+  return 0;
+}
diff --git a/y2022_bot3/control_loops/drivetrain/drivetrain_simulation_config.json b/y2022_bot3/control_loops/drivetrain/drivetrain_simulation_config.json
new file mode 100644
index 0000000..5ccc572
--- /dev/null
+++ b/y2022_bot3/control_loops/drivetrain/drivetrain_simulation_config.json
@@ -0,0 +1,6 @@
+{
+  "imports": [
+    "../../y2022_bot3.json",
+    "../../../frc971/control_loops/drivetrain/drivetrain_simulation_channels.json"
+  ]
+}
diff --git a/y2022_bot3/control_loops/drivetrain/trajectory_generator_main.cc b/y2022_bot3/control_loops/drivetrain/trajectory_generator_main.cc
new file mode 100644
index 0000000..644ae8d
--- /dev/null
+++ b/y2022_bot3/control_loops/drivetrain/trajectory_generator_main.cc
@@ -0,0 +1,40 @@
+#include <sys/resource.h>
+#include <sys/time.h>
+
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "frc971/control_loops/drivetrain/trajectory_generator.h"
+#include "y2022_bot3/control_loops/drivetrain/drivetrain_base.h"
+
+using ::frc971::control_loops::drivetrain::TrajectoryGenerator;
+
+DEFINE_bool(skip_renicing, false,
+            "If true, skip renicing the trajectory generator.");
+
+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());
+  TrajectoryGenerator generator(
+      &event_loop,
+      ::y2022_bot3::control_loops::drivetrain::GetDrivetrainConfig());
+
+  event_loop.OnRun([]() {
+    if (FLAGS_skip_renicing) {
+      LOG(WARNING) << "Ignoring request to renice to -20 due to "
+                      "--skip_renicing.";
+    } else {
+      errno = 0;
+      setpriority(PRIO_PROCESS, 0, -20);
+      PCHECK(errno == 0)
+          << ": Renicing to -20 failed, use --skip_renicing to skip renicing.";
+    }
+  });
+
+  event_loop.Run();
+
+  return 0;
+}
diff --git a/y2022_bot3/control_loops/python/BUILD b/y2022_bot3/control_loops/python/BUILD
new file mode 100644
index 0000000..e3e1beb
--- /dev/null
+++ b/y2022_bot3/control_loops/python/BUILD
@@ -0,0 +1,57 @@
+package(default_visibility = ["//y2022_bot3:__subpackages__"])
+
+py_binary(
+    name = "drivetrain",
+    srcs = [
+        "drivetrain.py",
+    ],
+    legacy_create_init = False,
+    target_compatible_with = ["@platforms//cpu:x86_64"],
+    deps = [
+        ":python_init",
+        "//external:python-gflags",
+        "//external:python-glog",
+        "//frc971/control_loops/python:drivetrain",
+    ],
+)
+
+py_binary(
+    name = "polydrivetrain",
+    srcs = [
+        "drivetrain.py",
+        "polydrivetrain.py",
+    ],
+    legacy_create_init = False,
+    target_compatible_with = ["@platforms//cpu:x86_64"],
+    deps = [
+        ":python_init",
+        "//external:python-gflags",
+        "//external:python-glog",
+        "//frc971/control_loops/python:polydrivetrain",
+    ],
+)
+
+py_library(
+    name = "polydrivetrain_lib",
+    srcs = [
+        "drivetrain.py",
+        "polydrivetrain.py",
+    ],
+    target_compatible_with = ["@platforms//cpu:x86_64"],
+    visibility = ["//visibility:public"],
+    deps = [
+        "//external:python-gflags",
+        "//external:python-glog",
+        "//frc971/control_loops/python:controls",
+        "//frc971/control_loops/python:drivetrain",
+        "//frc971/control_loops/python:polydrivetrain",
+    ],
+)
+
+py_library(
+    name = "python_init",
+    srcs = ["__init__.py"],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+    deps = ["//y2022_bot3/control_loops:python_init"],
+)
diff --git a/y2022_bot3/control_loops/python/__init__.py b/y2022_bot3/control_loops/python/__init__.py
new file mode 100644
index 0000000..e69de29
--- /dev/null
+++ b/y2022_bot3/control_loops/python/__init__.py
diff --git a/y2022_bot3/control_loops/python/drivetrain.py b/y2022_bot3/control_loops/python/drivetrain.py
new file mode 100644
index 0000000..76da623
--- /dev/null
+++ b/y2022_bot3/control_loops/python/drivetrain.py
@@ -0,0 +1,47 @@
+#!/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.0,
+    mass=58.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 / 54.0) * (22.0 / 56.0),
+    q_pos=0.24,
+    q_vel=2.5,
+    efficiency=0.80,
+    has_imu=True,
+    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], 'y2022_bot3', kDrivetrain)
+
+
+if __name__ == '__main__':
+    sys.exit(main(sys.argv))
diff --git a/y2022_bot3/control_loops/python/polydrivetrain.py b/y2022_bot3/control_loops/python/polydrivetrain.py
new file mode 100644
index 0000000..d7b2bd2
--- /dev/null
+++ b/y2022_bot3/control_loops/python/polydrivetrain.py
@@ -0,0 +1,31 @@
+#!/usr/bin/python3
+
+import sys
+from y2022_bot3.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], 'y2022_bot3',
+                                       drivetrain.kDrivetrain)
+
+if __name__ == '__main__':
+  argv = FLAGS(sys.argv)
+  glog.init()
+  sys.exit(main(argv))
diff --git a/y2022_bot3/control_loops/superstructure/BUILD b/y2022_bot3/control_loops/superstructure/BUILD
new file mode 100644
index 0000000..36a6c19
--- /dev/null
+++ b/y2022_bot3/control_loops/superstructure/BUILD
@@ -0,0 +1,130 @@
+load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library", "flatbuffer_ts_library")
+
+package(default_visibility = ["//visibility:public"])
+
+flatbuffer_cc_library(
+    name = "superstructure_goal_fbs",
+    srcs = [
+        "superstructure_goal.fbs",
+    ],
+    gen_reflections = 1,
+    includes = [
+        "//frc971/control_loops:control_loops_fbs_includes",
+        "//frc971/control_loops:profiled_subsystem_fbs_includes",
+    ],
+)
+
+flatbuffer_cc_library(
+    name = "superstructure_output_fbs",
+    srcs = [
+        "superstructure_output.fbs",
+    ],
+    gen_reflections = 1,
+)
+
+flatbuffer_cc_library(
+    name = "superstructure_status_fbs",
+    srcs = [
+        "superstructure_status.fbs",
+    ],
+    gen_reflections = 1,
+    includes = [
+        "//frc971/control_loops:control_loops_fbs_includes",
+        "//frc971/control_loops:profiled_subsystem_fbs_includes",
+    ],
+)
+
+flatbuffer_ts_library(
+    name = "superstructure_status_ts_fbs",
+    srcs = [
+        "superstructure_status.fbs",
+    ],
+    deps = [
+        "//frc971/control_loops:control_loops_ts_fbs",
+        "//frc971/control_loops:profiled_subsystem_ts_fbs",
+    ],
+)
+
+flatbuffer_cc_library(
+    name = "superstructure_position_fbs",
+    srcs = [
+        "superstructure_position.fbs",
+    ],
+    gen_reflections = 1,
+    includes = [
+        "//frc971/control_loops:control_loops_fbs_includes",
+        "//frc971/control_loops:profiled_subsystem_fbs_includes",
+    ],
+)
+
+cc_library(
+    name = "superstructure_lib",
+    srcs = [
+        "superstructure.cc",
+    ],
+    hdrs = [
+        "superstructure.h",
+    ],
+    deps = [
+        ":superstructure_goal_fbs",
+        ":superstructure_output_fbs",
+        ":superstructure_position_fbs",
+        ":superstructure_status_fbs",
+        "//aos:flatbuffer_merge",
+        "//aos/events:event_loop",
+        "//frc971/control_loops:control_loop",
+        "//frc971/control_loops/drivetrain:drivetrain_status_fbs",
+        "//y2022_bot3:constants",
+    ],
+)
+
+cc_binary(
+    name = "superstructure",
+    srcs = [
+        "superstructure_main.cc",
+    ],
+    deps = [
+        ":superstructure_lib",
+        "//aos:init",
+        "//aos/events:shm_event_loop",
+    ],
+)
+
+cc_test(
+    name = "superstructure_lib_test",
+    srcs = [
+        "superstructure_lib_test.cc",
+    ],
+    data = [
+        "//y2022_bot3:aos_config",
+    ],
+    deps = [
+        ":superstructure_goal_fbs",
+        ":superstructure_lib",
+        ":superstructure_output_fbs",
+        ":superstructure_position_fbs",
+        ":superstructure_status_fbs",
+        "//aos:math",
+        "//aos/events/logging:log_writer",
+        "//aos/testing:googletest",
+        "//aos/time",
+        "//frc971/control_loops:capped_test_plant",
+        "//frc971/control_loops:control_loop_test",
+        "//frc971/control_loops:position_sensor_sim",
+        "//frc971/control_loops:team_number_test_environment",
+        "//frc971/control_loops/drivetrain:drivetrain_status_fbs",
+    ],
+)
+
+cc_binary(
+    name = "superstructure_replay",
+    srcs = ["superstructure_replay.cc"],
+    deps = [
+        ":superstructure_lib",
+        "//aos:configuration",
+        "//aos:init",
+        "//aos/events:simulated_event_loop",
+        "//aos/events/logging:log_reader",
+        "//aos/network:team_number",
+    ],
+)
diff --git a/y2022_bot3/control_loops/superstructure/superstructure.cc b/y2022_bot3/control_loops/superstructure/superstructure.cc
new file mode 100644
index 0000000..5d12880
--- /dev/null
+++ b/y2022_bot3/control_loops/superstructure/superstructure.cc
@@ -0,0 +1,60 @@
+#include "y2022_bot3/control_loops/superstructure/superstructure.h"
+
+#include "aos/events/event_loop.h"
+#include "aos/flatbuffer_merge.h"
+#include "frc971/zeroing/wrap.h"
+
+namespace y2022_bot3 {
+namespace control_loops {
+namespace superstructure {
+
+using frc971::control_loops::AbsoluteEncoderProfiledJointStatus;
+using frc971::control_loops::PotAndAbsoluteEncoderProfiledJointStatus;
+using frc971::control_loops::RelativeEncoderProfiledJointStatus;
+
+Superstructure::Superstructure(::aos::EventLoop *event_loop,
+                               std::shared_ptr<const constants::Values> values,
+                               const ::std::string &name)
+    : frc971::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
+                                                                    name),
+      values_(values),
+      drivetrain_status_fetcher_(
+          event_loop->MakeFetcher<frc971::control_loops::drivetrain::Status>(
+              "/drivetrain")),
+      joystick_state_fetcher_(
+          event_loop->MakeFetcher<aos::JoystickState>("/aos")) {
+  event_loop->SetRuntimeRealtimePriority(30);
+}
+
+void Superstructure::RunIteration(const Goal *unsafe_goal,
+                                  const Position *position,
+                                  aos::Sender<Output>::Builder *output,
+                                  aos::Sender<Status>::Builder *status) {
+  (void)unsafe_goal;
+  (void)position;
+  if (WasReset()) {
+    AOS_LOG(ERROR, "WPILib reset, restarting\n");
+  }
+
+  OutputT output_struct;
+
+  if (joystick_state_fetcher_.Fetch() &&
+      joystick_state_fetcher_->has_alliance()) {
+    alliance_ = joystick_state_fetcher_->alliance();
+  }
+
+  drivetrain_status_fetcher_.Fetch();
+
+  output->CheckOk(output->Send(Output::Pack(*output->fbb(), &output_struct)));
+
+  Status::Builder status_builder = status->MakeBuilder<Status>();
+
+  status_builder.add_zeroed(true);
+  status_builder.add_estopped(false);
+
+  (void)status->Send(status_builder.Finish());
+}
+
+}  // namespace superstructure
+}  // namespace control_loops
+}  // namespace y2022_bot3
diff --git a/y2022_bot3/control_loops/superstructure/superstructure.h b/y2022_bot3/control_loops/superstructure/superstructure.h
new file mode 100644
index 0000000..91f80b4
--- /dev/null
+++ b/y2022_bot3/control_loops/superstructure/superstructure.h
@@ -0,0 +1,55 @@
+#ifndef Y2022_BOT3_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
+#define Y2022_BOT3_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
+
+#include "aos/events/event_loop.h"
+#include "frc971/control_loops/control_loop.h"
+#include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
+#include "y2022_bot3/constants.h"
+#include "y2022_bot3/control_loops/superstructure/superstructure_goal_generated.h"
+#include "y2022_bot3/control_loops/superstructure/superstructure_output_generated.h"
+#include "y2022_bot3/control_loops/superstructure/superstructure_position_generated.h"
+#include "y2022_bot3/control_loops/superstructure/superstructure_status_generated.h"
+
+namespace y2022_bot3 {
+namespace control_loops {
+namespace superstructure {
+
+class Superstructure
+    : public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
+ public:
+  using RelativeEncoderSubsystem =
+      ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystem<
+          ::frc971::zeroing::RelativeEncoderZeroingEstimator,
+          ::frc971::control_loops::RelativeEncoderProfiledJointStatus>;
+
+  using PotAndAbsoluteEncoderSubsystem =
+      ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystem<
+          ::frc971::zeroing::PotAndAbsoluteEncoderZeroingEstimator,
+          ::frc971::control_loops::PotAndAbsoluteEncoderProfiledJointStatus>;
+
+  explicit Superstructure(::aos::EventLoop *event_loop,
+                          std::shared_ptr<const constants::Values> values,
+                          const ::std::string &name = "/superstructure");
+
+ protected:
+  virtual void RunIteration(const Goal *unsafe_goal, const Position *position,
+                            aos::Sender<Output>::Builder *output,
+                            aos::Sender<Status>::Builder *status) override;
+
+ private:
+  std::shared_ptr<const constants::Values> values_;
+
+  aos::Fetcher<frc971::control_loops::drivetrain::Status>
+      drivetrain_status_fetcher_;
+  aos::Fetcher<aos::JoystickState> joystick_state_fetcher_;
+
+  aos::Alliance alliance_ = aos::Alliance::kInvalid;
+
+  DISALLOW_COPY_AND_ASSIGN(Superstructure);
+};
+
+}  // namespace superstructure
+}  // namespace control_loops
+}  // namespace y2022_bot3
+
+#endif  // Y2022_BOT3_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
diff --git a/y2022_bot3/control_loops/superstructure/superstructure_goal.fbs b/y2022_bot3/control_loops/superstructure/superstructure_goal.fbs
new file mode 100644
index 0000000..86e2e23
--- /dev/null
+++ b/y2022_bot3/control_loops/superstructure/superstructure_goal.fbs
@@ -0,0 +1,8 @@
+include "frc971/control_loops/profiled_subsystem.fbs";
+
+namespace y2022_bot3.control_loops.superstructure;
+
+table Goal {
+}
+
+root_type Goal;
diff --git a/y2022_bot3/control_loops/superstructure/superstructure_lib_test.cc b/y2022_bot3/control_loops/superstructure/superstructure_lib_test.cc
new file mode 100644
index 0000000..96f6273
--- /dev/null
+++ b/y2022_bot3/control_loops/superstructure/superstructure_lib_test.cc
@@ -0,0 +1,268 @@
+#include <chrono>
+#include <memory>
+
+#include "aos/events/logging/log_writer.h"
+#include "frc971/control_loops/capped_test_plant.h"
+#include "frc971/control_loops/control_loop_test.h"
+#include "frc971/control_loops/position_sensor_sim.h"
+#include "frc971/control_loops/team_number_test_environment.h"
+#include "gtest/gtest.h"
+#include "y2022_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+#include "y2022_bot3/control_loops/superstructure/superstructure.h"
+
+DEFINE_string(output_folder, "",
+              "If set, logs all channels to the provided logfile.");
+
+namespace y2022_bot3 {
+namespace control_loops {
+namespace superstructure {
+namespace testing {
+namespace chrono = std::chrono;
+namespace {
+constexpr double kNoiseScalar = 0.01;
+}
+
+using ::aos::monotonic_clock;
+using ::frc971::CreateProfileParameters;
+using ::frc971::control_loops::CappedTestPlant;
+using ::frc971::control_loops::
+    CreateStaticZeroingSingleDOFProfiledSubsystemGoal;
+using ::frc971::control_loops::PositionSensorSimulator;
+using ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal;
+typedef Superstructure::PotAndAbsoluteEncoderSubsystem
+    PotAndAbsoluteEncoderSubsystem;
+using DrivetrainStatus = ::frc971::control_loops::drivetrain::Status;
+
+template <typename SubsystemStatus, typename SubsystemState,
+          typename SubsystemConstants>
+
+// TODO(Henry) put this in frc971
+class SubsystemSimulator {
+ public:
+  SubsystemSimulator(CappedTestPlant *plant, PositionSensorSimulator encoder,
+                     const SubsystemConstants subsystem_constants,
+                     const frc971::constants::Range range,
+                     double encoder_offset, const chrono::nanoseconds dt)
+      : plant_(plant),
+        encoder_(encoder),
+        subsystem_constants_(subsystem_constants),
+        range_(range),
+        encoder_offset_(encoder_offset),
+        dt_(dt) {}
+
+  void InitializePosition(double start_pos) {
+    plant_->mutable_X(0, 0) = start_pos;
+    plant_->mutable_X(1, 0) = 0.0;
+
+    encoder_.Initialize(start_pos, kNoiseScalar, 0.0, encoder_offset_);
+  }
+
+  // Simulates the superstructure for a single timestep.
+  void Simulate(double voltage, const SubsystemStatus *status) {
+    double last_velocity = plant_->X(1, 0);
+
+    const double voltage_check =
+        (static_cast<SubsystemState>(status->state()) ==
+         SubsystemState::RUNNING)
+            ? subsystem_constants_.subsystem_params.operating_voltage
+            : subsystem_constants_.subsystem_params.zeroing_voltage;
+
+    EXPECT_NEAR(voltage, 0.0, voltage_check);
+
+    ::Eigen::Matrix<double, 1, 1> U;
+    U << voltage + plant_->voltage_offset();
+    plant_->Update(U);
+
+    const double position = plant_->Y(0, 0);
+
+    encoder_.MoveTo(position);
+
+    EXPECT_GE(position, range_.lower_hard);
+    EXPECT_LE(position, range_.upper_hard);
+
+    const double loop_time = ::aos::time::DurationInSeconds(dt_);
+
+    const double velocity = plant_->X(1, 0);
+    const double acceleration = (velocity - last_velocity) / loop_time;
+
+    EXPECT_GE(peak_acceleration_, acceleration);
+    EXPECT_LE(-peak_acceleration_, acceleration);
+    EXPECT_GE(peak_velocity_, velocity);
+    EXPECT_LE(-peak_velocity_, velocity);
+  }
+
+  void set_peak_acceleration(double value) { peak_acceleration_ = value; }
+  void set_peak_velocity(double value) { peak_velocity_ = value; }
+
+  void set_controller_index(size_t index) { plant_->set_index(index); }
+
+  PositionSensorSimulator *encoder() { return &encoder_; }
+
+ private:
+  std::unique_ptr<CappedTestPlant> plant_;
+  PositionSensorSimulator encoder_;
+  const SubsystemConstants subsystem_constants_;
+  const frc971::constants::Range range_;
+
+  double encoder_offset_ = 0.0;
+
+  double peak_velocity_ = std::numeric_limits<double>::infinity();
+  double peak_acceleration_ = std::numeric_limits<double>::infinity();
+
+  const chrono::nanoseconds dt_;
+};
+
+using PotAndAbsoluteEncoderSimulator = SubsystemSimulator<
+    frc971::control_loops::PotAndAbsoluteEncoderProfiledJointStatus,
+    PotAndAbsoluteEncoderSubsystem::State,
+    constants::Values::PotAndAbsEncoderConstants>;
+
+// Class which simulates the superstructure and sends out queue messages with
+// the position.
+class SuperstructureSimulation {
+ public:
+  SuperstructureSimulation(::aos::EventLoop *event_loop,
+                           std::shared_ptr<const constants::Values> values,
+                           chrono::nanoseconds dt)
+      : event_loop_(event_loop),
+        dt_(dt),
+        superstructure_position_sender_(
+            event_loop_->MakeSender<Position>("/superstructure")),
+        superstructure_status_fetcher_(
+            event_loop_->MakeFetcher<Status>("/superstructure")),
+        superstructure_output_fetcher_(
+            event_loop_->MakeFetcher<Output>("/superstructure")) {
+    phased_loop_handle_ = event_loop_->AddPhasedLoop(
+        [this](int) {
+          // Skip this the first time.
+          if (!first_) {
+            EXPECT_TRUE(superstructure_output_fetcher_.Fetch());
+            EXPECT_TRUE(superstructure_status_fetcher_.Fetch());
+          }
+          first_ = false;
+          SendPositionMessage();
+        },
+        dt);
+    (void)values;
+    (void)dt_;
+  }
+
+  // Sends a queue message with the position of the superstructure.
+  void SendPositionMessage() {
+    ::aos::Sender<Position>::Builder builder =
+        superstructure_position_sender_.MakeBuilder();
+  }
+
+ private:
+  ::aos::EventLoop *event_loop_;
+  const chrono::nanoseconds dt_;
+  ::aos::PhasedLoopHandler *phased_loop_handle_ = nullptr;
+
+  ::aos::Sender<Position> superstructure_position_sender_;
+  ::aos::Fetcher<Status> superstructure_status_fetcher_;
+  ::aos::Fetcher<Output> superstructure_output_fetcher_;
+
+  bool first_ = true;
+};
+
+class SuperstructureTest : public ::frc971::testing::ControlLoopTest {
+ public:
+  SuperstructureTest()
+      : ::frc971::testing::ControlLoopTest(
+            aos::configuration::ReadConfig("y2022_bot3/aos_config.json"),
+            std::chrono::microseconds(5050)),
+        values_(std::make_shared<constants::Values>(constants::MakeValues(
+            frc971::control_loops::testing::kTeamNumber))),
+        roborio_(aos::configuration::GetNode(configuration(), "roborio")),
+        superstructure_event_loop(MakeEventLoop("Superstructure", roborio_)),
+        superstructure_(superstructure_event_loop.get(), values_),
+        test_event_loop_(MakeEventLoop("test", roborio_)),
+        superstructure_goal_fetcher_(
+            test_event_loop_->MakeFetcher<Goal>("/superstructure")),
+        superstructure_goal_sender_(
+            test_event_loop_->MakeSender<Goal>("/superstructure")),
+        superstructure_status_fetcher_(
+            test_event_loop_->MakeFetcher<Status>("/superstructure")),
+        superstructure_output_fetcher_(
+            test_event_loop_->MakeFetcher<Output>("/superstructure")),
+        superstructure_position_fetcher_(
+            test_event_loop_->MakeFetcher<Position>("/superstructure")),
+        superstructure_position_sender_(
+            test_event_loop_->MakeSender<Position>("/superstructure")),
+        drivetrain_status_sender_(
+            test_event_loop_->MakeSender<DrivetrainStatus>("/drivetrain")),
+        superstructure_plant_event_loop_(MakeEventLoop("plant", roborio_)),
+        superstructure_plant_(superstructure_plant_event_loop_.get(), values_,
+                              dt()) {
+    set_team_id(frc971::control_loops::testing::kTeamNumber);
+
+    SetEnabled(true);
+  }
+
+  void CheckIfZeroed() {
+    superstructure_status_fetcher_.Fetch();
+    ASSERT_TRUE(superstructure_status_fetcher_.get()->zeroed());
+  }
+
+  void WaitUntilZeroed() {
+    int i = 0;
+    do {
+      i++;
+      RunFor(dt());
+      superstructure_status_fetcher_.Fetch();
+      // 2 Seconds
+      ASSERT_LE(i, 2.0 / ::aos::time::DurationInSeconds(dt()));
+
+      // Since there is a delay when sending running, make sure we have a
+      // status before checking it.
+    } while (superstructure_status_fetcher_.get() == nullptr ||
+             !superstructure_status_fetcher_.get()->zeroed());
+  }
+
+  void SendRobotVelocity(double robot_velocity) {
+    SendDrivetrainStatus(robot_velocity, {0.0, 0.0}, 0.0);
+  }
+
+  void SendDrivetrainStatus(double robot_velocity, Eigen::Vector2d pos,
+                            double theta) {
+    // Send a robot velocity to test compensation
+    auto builder = drivetrain_status_sender_.MakeBuilder();
+    auto drivetrain_status_builder = builder.MakeBuilder<DrivetrainStatus>();
+    drivetrain_status_builder.add_robot_speed(robot_velocity);
+    drivetrain_status_builder.add_estimated_left_velocity(robot_velocity);
+    drivetrain_status_builder.add_estimated_right_velocity(robot_velocity);
+    drivetrain_status_builder.add_x(pos.x());
+    drivetrain_status_builder.add_y(pos.y());
+    drivetrain_status_builder.add_theta(theta);
+    builder.CheckOk(builder.Send(drivetrain_status_builder.Finish()));
+  }
+
+  std::shared_ptr<const constants::Values> values_;
+
+  const aos::Node *const roborio_;
+
+  ::std::unique_ptr<::aos::EventLoop> superstructure_event_loop;
+  ::y2022_bot3::control_loops::superstructure::Superstructure superstructure_;
+  ::std::unique_ptr<::aos::EventLoop> test_event_loop_;
+  ::aos::PhasedLoopHandler *phased_loop_handle_ = nullptr;
+
+  ::aos::Fetcher<Goal> superstructure_goal_fetcher_;
+  ::aos::Sender<Goal> superstructure_goal_sender_;
+  ::aos::Fetcher<Status> superstructure_status_fetcher_;
+  ::aos::Fetcher<Output> superstructure_output_fetcher_;
+  ::aos::Fetcher<Position> superstructure_position_fetcher_;
+  ::aos::Sender<Position> superstructure_position_sender_;
+  ::aos::Sender<DrivetrainStatus> drivetrain_status_sender_;
+
+  ::std::unique_ptr<::aos::EventLoop> superstructure_plant_event_loop_;
+  SuperstructureSimulation superstructure_plant_;
+
+  std::unique_ptr<aos::EventLoop> logger_event_loop_;
+  std::unique_ptr<aos::logger::Logger> logger_;
+
+};  // namespace testing
+
+}  // namespace testing
+}  // namespace superstructure
+}  // namespace control_loops
+}  // namespace y2022_bot3
diff --git a/y2022_bot3/control_loops/superstructure/superstructure_main.cc b/y2022_bot3/control_loops/superstructure/superstructure_main.cc
new file mode 100644
index 0000000..7a82237
--- /dev/null
+++ b/y2022_bot3/control_loops/superstructure/superstructure_main.cc
@@ -0,0 +1,21 @@
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "y2022_bot3/control_loops/superstructure/superstructure.h"
+
+int main(int argc, char **argv) {
+  ::aos::InitGoogle(&argc, &argv);
+
+  aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+      aos::configuration::ReadConfig("aos_config.json");
+
+  ::aos::ShmEventLoop event_loop(&config.message());
+  std::shared_ptr<const y2022_bot3::constants::Values> values =
+      std::make_shared<const y2022_bot3::constants::Values>(
+          y2022_bot3::constants::MakeValues());
+  ::y2022_bot3::control_loops::superstructure::Superstructure superstructure(
+      &event_loop, values);
+
+  event_loop.Run();
+
+  return 0;
+}
diff --git a/y2022_bot3/control_loops/superstructure/superstructure_output.fbs b/y2022_bot3/control_loops/superstructure/superstructure_output.fbs
new file mode 100644
index 0000000..9b96b89
--- /dev/null
+++ b/y2022_bot3/control_loops/superstructure/superstructure_output.fbs
@@ -0,0 +1,6 @@
+namespace y2022_bot3.control_loops.superstructure;
+
+table Output {
+}
+
+root_type Output;
diff --git a/y2022_bot3/control_loops/superstructure/superstructure_position.fbs b/y2022_bot3/control_loops/superstructure/superstructure_position.fbs
new file mode 100644
index 0000000..67838a2
--- /dev/null
+++ b/y2022_bot3/control_loops/superstructure/superstructure_position.fbs
@@ -0,0 +1,8 @@
+include "frc971/control_loops/control_loops.fbs";
+
+namespace y2022_bot3.control_loops.superstructure;
+
+table Position {
+}
+
+root_type Position;
diff --git a/y2022_bot3/control_loops/superstructure/superstructure_replay.cc b/y2022_bot3/control_loops/superstructure/superstructure_replay.cc
new file mode 100644
index 0000000..4e041fc
--- /dev/null
+++ b/y2022_bot3/control_loops/superstructure/superstructure_replay.cc
@@ -0,0 +1,75 @@
+// This binary allows us to replay the superstructure code over existing
+// logfile. When you run this code, it generates a new logfile with the data all
+// replayed, so that it can then be run through the plotting tool or analyzed
+// in some other way. The original superstructure status data will be on the
+// /original/superstructure channel.
+#include "aos/events/logging/log_reader.h"
+#include "aos/events/logging/log_writer.h"
+#include "aos/events/simulated_event_loop.h"
+#include "aos/init.h"
+#include "aos/json_to_flatbuffer.h"
+#include "aos/logging/log_message_generated.h"
+#include "aos/network/team_number.h"
+#include "gflags/gflags.h"
+#include "y2022_bot3/constants.h"
+#include "y2022_bot3/control_loops/superstructure/superstructure.h"
+
+DEFINE_int32(team, 971, "Team number to use for logfile replay.");
+DEFINE_string(output_folder, "/tmp/superstructure_replay/",
+              "Logs all channels to the provided logfile.");
+
+int main(int argc, char **argv) {
+  aos::InitGoogle(&argc, &argv);
+
+  aos::network::OverrideTeamNumber(FLAGS_team);
+
+  // open logfiles
+  aos::logger::LogReader reader(
+      aos::logger::SortParts(aos::logger::FindLogs(argc, argv)));
+  // TODO(james): Actually enforce not sending on the same buses as the logfile
+  // spews out.
+  reader.RemapLoggedChannel("/superstructure",
+                            "y2022_bot3.control_loops.superstructure.Status");
+  reader.RemapLoggedChannel("/superstructure",
+                            "y2022_bot3.control_loops.superstructure.Output");
+
+  aos::SimulatedEventLoopFactory factory(reader.configuration());
+  reader.Register(&factory);
+
+  aos::NodeEventLoopFactory *roborio =
+      factory.GetNodeEventLoopFactory("roborio");
+
+  unlink(FLAGS_output_folder.c_str());
+  std::unique_ptr<aos::EventLoop> logger_event_loop =
+      roborio->MakeEventLoop("logger");
+  auto logger = std::make_unique<aos::logger::Logger>(logger_event_loop.get());
+  logger->StartLoggingOnRun(FLAGS_output_folder);
+
+  roborio->OnStartup([roborio]() {
+    roborio->AlwaysStart<
+        y2022_bot3::control_loops::superstructure::Superstructure>(
+        "superstructure", std::make_shared<y2022_bot3::constants::Values>(
+                              y2022_bot3::constants::MakeValues()));
+  });
+
+  std::unique_ptr<aos::EventLoop> print_loop = roborio->MakeEventLoop("print");
+  print_loop->SkipAosLog();
+  print_loop->MakeWatcher(
+      "/aos", [&print_loop](const aos::logging::LogMessageFbs &msg) {
+        LOG(INFO) << print_loop->context().monotonic_event_time << " "
+                  << aos::FlatbufferToJson(&msg);
+      });
+  print_loop->MakeWatcher(
+      "/superstructure",
+      [&](const y2022_bot3::control_loops::superstructure::Status &status) {
+        if (status.estopped()) {
+          LOG(ERROR) << "Estopped";
+        }
+      });
+
+  factory.Run();
+
+  reader.Deregister();
+
+  return 0;
+}
diff --git a/y2022_bot3/control_loops/superstructure/superstructure_status.fbs b/y2022_bot3/control_loops/superstructure/superstructure_status.fbs
new file mode 100644
index 0000000..89af435
--- /dev/null
+++ b/y2022_bot3/control_loops/superstructure/superstructure_status.fbs
@@ -0,0 +1,14 @@
+include "frc971/control_loops/control_loops.fbs";
+include "frc971/control_loops/profiled_subsystem.fbs";
+
+namespace y2022_bot3.control_loops.superstructure;
+
+table Status {
+  // All subsystems know their location.
+  zeroed:bool (id: 0);
+
+  // If true, we have aborted. This is the or of all subsystem estops.
+  estopped:bool (id: 1);
+}
+
+root_type Status;
diff --git a/y2022_bot3/joystick_reader.cc b/y2022_bot3/joystick_reader.cc
new file mode 100644
index 0000000..25875eb
--- /dev/null
+++ b/y2022_bot3/joystick_reader.cc
@@ -0,0 +1,78 @@
+#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/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 "y2022_bot3/control_loops/drivetrain/drivetrain_base.h"
+#include "y2022_bot3/control_loops/superstructure/superstructure_goal_generated.h"
+#include "y2022_bot3/control_loops/superstructure/superstructure_status_generated.h"
+
+using frc971::input::driver_station::ButtonLocation;
+using frc971::input::driver_station::ControlBit;
+using frc971::input::driver_station::JoystickAxis;
+using frc971::input::driver_station::POVLocation;
+
+namespace y2022_bot3 {
+namespace input {
+namespace joysticks {
+
+namespace superstructure = y2022_bot3::control_loops::superstructure;
+
+class Reader : public ::frc971::input::ActionJoystickInput {
+ public:
+  Reader(::aos::EventLoop *event_loop)
+      : ::frc971::input::ActionJoystickInput(
+            event_loop,
+            ::y2022_bot3::control_loops::drivetrain::GetDrivetrainConfig(),
+            ::frc971::input::DrivetrainInputReader::InputType::kPistol, {}),
+        superstructure_goal_sender_(
+            event_loop->MakeSender<superstructure::Goal>("/superstructure")),
+        superstructure_status_fetcher_(
+            event_loop->MakeFetcher<superstructure::Status>(
+                "/superstructure")) {}
+
+  void AutoEnded() override { AOS_LOG(INFO, "Auto ended.\n"); }
+
+  void HandleTeleop(
+      const ::frc971::input::driver_station::Data & /*data*/) override {
+    superstructure_status_fetcher_.Fetch();
+    if (!superstructure_status_fetcher_.get()) {
+      AOS_LOG(ERROR, "Got no superstructure status message.\n");
+      return;
+    }
+  }
+
+ private:
+  ::aos::Sender<superstructure::Goal> superstructure_goal_sender_;
+
+  ::aos::Fetcher<superstructure::Status> superstructure_status_fetcher_;
+};
+
+}  // namespace joysticks
+}  // namespace input
+}  // namespace y2022_bot3
+
+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());
+  ::y2022_bot3::input::joysticks::Reader reader(&event_loop);
+
+  event_loop.Run();
+
+  return 0;
+}
diff --git a/y2022_bot3/log_web_proxy.sh b/y2022_bot3/log_web_proxy.sh
new file mode 100755
index 0000000..4abdc19
--- /dev/null
+++ b/y2022_bot3/log_web_proxy.sh
@@ -0,0 +1 @@
+./aos/network/log_web_proxy_main --data_dir=y2022_bot3/www $@
diff --git a/y2022_bot3/wpilib_interface.cc b/y2022_bot3/wpilib_interface.cc
new file mode 100644
index 0000000..0366256
--- /dev/null
+++ b/y2022_bot3/wpilib_interface.cc
@@ -0,0 +1,321 @@
+#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 "aos/commonmath.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 "ctre/phoenix/motorcontrol/can/TalonFX.h"
+#include "ctre/phoenix/motorcontrol/can/TalonSRX.h"
+#include "frc971/autonomous/auto_mode_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/dma.h"
+#include "frc971/wpilib/drivetrain_writer.h"
+#include "frc971/wpilib/encoder_and_potentiometer.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 "y2022_bot3/constants.h"
+#include "y2022_bot3/control_loops/superstructure/superstructure_output_generated.h"
+#include "y2022_bot3/control_loops/superstructure/superstructure_position_generated.h"
+
+using ::aos::monotonic_clock;
+using ::y2022_bot3::constants::Values;
+namespace superstructure = ::y2022_bot3::control_loops::superstructure;
+namespace chrono = ::std::chrono;
+using std::make_unique;
+
+namespace y2022_bot3 {
+namespace wpilib {
+namespace {
+
+constexpr double kMaxBringupPower = 12.0;
+
+// TODO(Brian): Fix the interpretation of the result of GetRaw here and in the
+// DMA stuff and then removing the * 2.0 in *_translate.
+// The low bit is direction.
+
+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 =
+    Values::kMaxDrivetrainEncoderPulsesPerSecond();
+static_assert(kMaxFastEncoderPulsesPerSecond <= 1300000,
+              "fast encoders are too fast");
+constexpr double kMaxMediumEncoderPulsesPerSecond = 0;
+
+static_assert(kMaxMediumEncoderPulsesPerSecond <= 400000,
+              "medium 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")),
+        superstructure_position_sender_(
+            event_loop->MakeSender<superstructure::Position>(
+                "/superstructure")),
+        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);
+    UpdateMediumEncoderFilterHz(kMaxMediumEncoderPulsesPerSecond);
+  }
+
+  void Start() override {
+    // TODO(Ravago): Figure out why adding multiple DMA readers results in weird
+    // behavior
+    // AddToDMA(&imu_heading_reader_);
+    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_heading_input(::std::unique_ptr<frc::DigitalInput> sensor) {
+    imu_heading_input_ = ::std::move(sensor);
+    imu_heading_reader_.set_input(imu_heading_input_.get());
+  }
+
+  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 {
+    {
+      auto builder = superstructure_position_sender_.MakeBuilder();
+      superstructure::Position::Builder position_builder =
+          builder.MakeBuilder<superstructure::Position>();
+      builder.CheckOk(builder.Send(position_builder.Finish()));
+    }
+
+    {
+      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 heading_duty_cycle =
+          imu_heading_reader_.last_width() * kPWMFrequencyHz;
+      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_heading_duty_cycle =
+          (heading_duty_cycle - kScaledRangeLow) * kDutyCycleScale;
+      double rescaled_velocity_duty_cycle =
+          (velocity_duty_cycle - kScaledRangeLow) * kDutyCycleScale;
+
+      if (!std::isnan(rescaled_heading_duty_cycle)) {
+        gyro_reading_builder.add_angle(rescaled_heading_duty_cycle *
+                                       (2.0 * M_PI));
+      }
+      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()));
+    }
+  }
+
+ private:
+  std::shared_ptr<const Values> values_;
+
+  aos::Sender<frc971::autonomous::AutonomousMode> auto_mode_sender_;
+  aos::Sender<superstructure::Position> superstructure_position_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_heading_input_, imu_yaw_rate_input_;
+
+  frc971::wpilib::DMAPulseWidthReader imu_heading_reader_, imu_yaw_rate_reader_;
+};
+
+class SuperstructureWriter
+    : public ::frc971::wpilib::LoopOutputHandler<superstructure::Output> {
+ public:
+  SuperstructureWriter(aos::EventLoop *event_loop)
+      : frc971::wpilib::LoopOutputHandler<superstructure::Output>(
+            event_loop, "/superstructure") {}
+
+ private:
+  void Stop() override { AOS_LOG(WARNING, "Superstructure output too old.\n"); }
+
+  void Write(const superstructure::Output &output) override { (void)output; }
+
+  static void WriteCan(const double voltage,
+                       ::ctre::phoenix::motorcontrol::can::TalonFX *falcon) {
+    falcon->Set(
+        ctre::phoenix::motorcontrol::ControlMode::PercentOutput,
+        std::clamp(voltage, -kMaxBringupPower, kMaxBringupPower) / 12.0);
+  }
+
+  template <typename T>
+  static void WritePwm(const double voltage, T *motor) {
+    motor->SetSpeed(std::clamp(voltage, -kMaxBringupPower, kMaxBringupPower) /
+                    12.0);
+  }
+};
+
+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);
+    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_heading_input(make_unique<frc::DigitalInput>(9));
+    sensor_reader.set_yaw_rate_input(make_unique<frc::DigitalInput>(8));
+
+    AddLoop(&sensor_reader_event_loop);
+
+    // Thread 4.
+    ::aos::ShmEventLoop output_event_loop(&config.message());
+    ::frc971::wpilib::DrivetrainWriter drivetrain_writer(&output_event_loop);
+    drivetrain_writer.set_left_controller0(
+        ::std::unique_ptr<::frc::VictorSP>(new ::frc::VictorSP(0)), false);
+    drivetrain_writer.set_right_controller0(
+        ::std::unique_ptr<::frc::VictorSP>(new ::frc::VictorSP(1)), true);
+
+    SuperstructureWriter superstructure_writer(&output_event_loop);
+
+    AddLoop(&output_event_loop);
+
+    // Thread 5.
+    RunLoops();
+  }
+};
+
+}  // namespace wpilib
+}  // namespace y2022_bot3
+
+AOS_ROBOT_CLASS(::y2022_bot3::wpilib::WPILibRobot);
diff --git a/y2022_bot3/y2022_bot3.json b/y2022_bot3/y2022_bot3.json
new file mode 100644
index 0000000..eebfe62
--- /dev/null
+++ b/y2022_bot3/y2022_bot3.json
@@ -0,0 +1,18 @@
+{
+  "channel_storage_duration": 2000000000,
+  "maps": [
+    {
+      "match": {
+        "name": "/aos",
+        "type": "aos.RobotState"
+      },
+      "rename": {
+        "name": "/roborio/aos"
+      }
+    }
+  ],
+  "imports": [
+    "y2022_bot3_roborio.json",
+    "y2022_bot3_imu.json"
+  ]
+}
diff --git a/y2022_bot3/y2022_bot3_imu.json b/y2022_bot3/y2022_bot3_imu.json
new file mode 100644
index 0000000..5673195
--- /dev/null
+++ b/y2022_bot3/y2022_bot3_imu.json
@@ -0,0 +1,235 @@
+{
+  "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",
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "frequency": 50,
+      "num_senders": 20,
+      "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/imu/aos/aos-starter-Status",
+      "type": "aos.message_bridge.RemoteMessage",
+      "frequency": 100,
+      "source_node": "imu",
+      "max_size": 208
+    },
+    {
+      "name": "/imu/aos",
+      "type": "aos.starter.StarterRpc",
+      "source_node": "imu",
+      "frequency": 10,
+      "num_senders": 2,
+      "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/imu/aos/aos-starter-StarterRpc",
+      "type": "aos.message_bridge.RemoteMessage",
+      "frequency": 20,
+      "source_node": "imu",
+      "max_size": 208
+    },
+    {
+      "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"
+      ],
+      "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": "/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/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": "/roborio/aos/remote_timestamps/imu/roborio/aos/aos-starter-Status",
+      "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",
+      "executable_name": "message_bridge_client",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "localizer",
+      "executable_name": "localizer_main",
+      /* TODO(james): Remove this once confident in the accelerometer code. */
+      "args": ["--ignore_accelerometer"],
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "imu",
+      "executable_name": "imu_main",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "message_bridge_server",
+      "executable_name": "message_bridge_server",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "localizer_logger",
+      "executable_name": "logger_main",
+      "args": ["--logging_folder", "", "--snappy_compress"],
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "web_proxy",
+      "executable_name": "web_proxy_main",
+      "nodes": [
+        "imu"
+      ]
+    }
+  ],
+  "maps": [
+    {
+      "match": {
+        "name": "/aos*",
+        "source_node": "imu"
+      },
+      "rename": {
+        "name": "/imu/aos"
+      }
+    }
+  ],
+  "nodes": [
+    {
+      "name": "imu",
+      "hostname": "imu",
+      "hostnames": [
+        "pi-971-5",
+        "pi-7971-5",
+        "pi-8971-5",
+        "pi-9971-5"
+      ],
+      "port": 9971
+    },
+    {
+      "name": "roborio"
+    }
+  ]
+}
diff --git a/y2022_bot3/y2022_bot3_roborio.json b/y2022_bot3/y2022_bot3_roborio.json
new file mode 100644
index 0000000..5f0b5ae
--- /dev/null
+++ b/y2022_bot3/y2022_bot3_roborio.json
@@ -0,0 +1,505 @@
+{
+  "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,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "roborio"
+          ]
+        }
+      ]
+    },
+    {
+      "name": "/roborio/aos/remote_timestamps/imu/roborio/aos/aos-JoystickState",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "roborio",
+      "logger": "NOT_LOGGED",
+      "frequency": 200,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
+      "name": "/roborio/aos/remote_timestamps/logger/roborio/aos/aos-JoystickState",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "roborio",
+      "logger": "NOT_LOGGED",
+      "frequency": 200,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "aos.RobotState",
+      "source_node": "roborio",
+      "frequency": 200
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "aos.timing.Report",
+      "source_node": "roborio",
+      "frequency": 50,
+      "num_senders": 20,
+      "max_size": 4096
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "aos.logging.LogMessageFbs",
+      "source_node": "roborio",
+      "frequency": 500,
+      "max_size": 344,
+      "num_senders": 20
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "aos.starter.Status",
+      "source_node": "roborio",
+      "frequency": 50,
+      "num_senders": 20,
+      "max_size": 2000,
+      "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/logger/roborio/aos/aos-starter-Status",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "roborio",
+      "logger": "NOT_LOGGED",
+      "frequency": 20,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "aos.starter.StarterRpc",
+      "source_node": "roborio",
+      "frequency": 10,
+      "max_size": 400,
+      "num_senders": 2,
+      "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/logger/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": "/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/logger/roborio/aos/aos-message_bridge-Timestamp",
+      "type": "aos.message_bridge.RemoteMessage",
+      "frequency": 200,
+      "source_node": "roborio"
+    },
+    {
+      "name": "/roborio/aos/remote_timestamps/imu/roborio/aos/aos-message_bridge-Timestamp",
+      "type": "aos.message_bridge.RemoteMessage",
+      "frequency": 20,
+      "source_node": "roborio",
+      "max_size": 208
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "aos.message_bridge.Timestamp",
+      "source_node": "roborio",
+      "frequency": 15,
+      "num_senders": 2,
+      "max_size": 512,
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "imu"
+      ],
+      "destination_nodes": [
+        {
+          "name": "imu",
+          "priority": 1,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "roborio"
+          ],
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/superstructure",
+      "type": "y2022_bot3.control_loops.superstructure.Goal",
+      "source_node": "roborio",
+      "frequency": 200,
+      "max_size": 512
+    },
+    {
+      "name": "/superstructure",
+      "type": "y2022_bot3.control_loops.superstructure.Status",
+      "source_node": "roborio",
+      "frequency": 400,
+      "num_senders": 2,
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "imu"
+      ],
+      "destination_nodes": [
+        {
+          "name": "imu",
+          "priority": 5,
+          "time_to_live": 50000000,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "roborio"
+          ]
+        }
+      ]
+    },
+    {
+      "name": "/roborio/aos/remote_timestamps/imu/superstructure/y2022_bot3-control_loops-superstructure-Status",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "roborio",
+      "logger": "NOT_LOGGED",
+      "frequency": 400,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
+      "name": "/roborio/aos/remote_timestamps/logger/superstructure/y2022_bot3-control_loops-superstructure-Status",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "roborio",
+      "logger": "NOT_LOGGED",
+      "frequency": 400,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
+      "name": "/superstructure",
+      "type": "y2022_bot3.control_loops.superstructure.Output",
+      "source_node": "roborio",
+      "frequency": 200,
+      "num_senders": 2,
+      "max_size": 224
+    },
+    {
+      "name": "/superstructure",
+      "type": "y2022_bot3.control_loops.superstructure.Position",
+      "source_node": "roborio",
+      "frequency": 200,
+      "num_senders": 2,
+      "max_size": 448
+    },
+    {
+      "name": "/drivetrain",
+      "type": "frc971.sensors.GyroReading",
+      "source_node": "roborio",
+      "frequency": 200,
+      "num_senders": 2
+    },
+    {
+      "name": "/drivetrain",
+      "type": "frc971.sensors.Uid",
+      "source_node": "roborio",
+      "frequency": 200,
+      "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": 200
+    },
+    {
+      "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,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "imu"
+          ],
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/roborio/aos/remote_timestamps/imu/drivetrain/frc971-control_loops-drivetrain-Output",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "roborio",
+      "logger": "NOT_LOGGED",
+      "frequency": 400,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
+      "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": 200,
+      "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": [
+            "imu"
+          ],
+          "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": "/drivetrain",
+      "type": "y2019.control_loops.drivetrain.TargetSelectorHint",
+      "source_node": "roborio"
+    },
+    {
+      "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": 200
+    },
+    {
+      "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
+    }
+  ],
+  "applications": [
+    {
+      "name": "drivetrain",
+      "executable_name": "drivetrain",
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "trajectory_generator",
+      "executable_name": "trajectory_generator",
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "superstructure",
+      "executable_name": "superstructure",
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "joystick_reader",
+      "executable_name": "joystick_reader",
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "wpilib_interface",
+      "executable_name": "wpilib_interface",
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "autonomous_action",
+      "executable_name": "autonomous_action",
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "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.sh",
+      "args": ["--rt_priority=16"],
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "message_bridge_server",
+      "executable_name": "message_bridge_server",
+      "args": ["--rt_priority=16"],
+      "nodes": [
+        "roborio"
+      ]
+    },
+    {
+      "name": "logger",
+      "executable_name": "logger_main",
+      "args": ["--snappy_compress"],
+      "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"
+    }
+  ]
+}