Merge "Added set functions for turret and catapult falcons"
diff --git a/.bazelrc b/.bazelrc
index 1c6dbde..b12d5b2 100644
--- a/.bazelrc
+++ b/.bazelrc
@@ -15,7 +15,6 @@
 build --strip=never
 
 build --noincompatible_disable_nocopts
-common --noincompatible_restrict_string_escapes
 
 # Use the malloc we want.
 build --custom_malloc=//tools/cpp:malloc
@@ -23,13 +22,15 @@
 # Shortcuts for selecting the target platform.
 build:k8 --platforms=//tools/platforms:linux_x86
 build:roborio --platforms=//tools/platforms:linux_roborio
+build:roborio --platform_suffix=-roborio
 build:armv7 --platforms=//tools/platforms:linux_armv7
+build:armv7 --platform_suffix=-armv7
 build:arm64 --platforms=//tools/platforms:linux_arm64
+build:arm64 --platform_suffix=-arm64
 build:cortex-m4f --platforms=//tools/platforms:cortex_m4f
+build:cortex-m4f --platform_suffix=-cortex-m4f
 build:rp2040 --platforms=//tools/platforms:rp2040
-
-# Without this, we end up rebuilding from scratch every time we change compilers.  This is needed to make --cpu work (even though it shouldn't be used).
-build --crosstool_top=@//tools/cpp:toolchain --host_crosstool_top=@//tools/cpp:toolchain
+build:rp2040 --platform_suffix=-rp2040
 
 build:asan --copt -fsanitize=address
 build:asan --linkopt -fsanitize=address --linkopt -ldl
@@ -78,7 +79,7 @@
 # Dump the output of the failing test to stdout.
 test --test_output=errors
 
-build --experimental_sandbox_base=/dev/shm/
+build --sandbox_base=/dev/shm/
 build --experimental_multi_threaded_digest
 
 build --sandbox_fake_hostname=true
@@ -92,7 +93,7 @@
 startup --host_jvm_args=-Dbazel.DigestFunction=SHA256
 
 build --spawn_strategy=linux-sandbox
-build --experimental_sandbox_default_allow_network=false
+build --sandbox_default_allow_network=false
 
 build --strategy=TypeScriptCompile=worker --strategy=AngularTemplateCompile=worker
 
@@ -100,7 +101,7 @@
 # Note that this doesn't quite work fully, but it should. See
 # https://github.com/bazelbuild/bazel/issues/6341 for ongoing discussion with
 # upstream about this.
-build --javabase=@openjdk_linux_archive//:jdk --host_javabase=@openjdk_linux_archive//:jdk
+build --java_runtime_version=openjdk_9 --tool_java_runtime_version=openjdk_9
 
 # Prevent falling back to the host JDK.
 startup --noautodetect_server_javabase
diff --git a/BUILD b/BUILD
index 91997b9..e7fa267 100644
--- a/BUILD
+++ b/BUILD
@@ -11,6 +11,7 @@
 # gazelle:go_generate_proto false
 # gazelle:exclude third_party
 # gazelle:exclude external
+# gazelle:resolve go github.com/frc971/971-Robot-Code/build_tests/fbs //build_tests:test_go_fbs
 
 gazelle(
     name = "gazelle",
diff --git a/WORKSPACE b/WORKSPACE
index 1ea9cce..514fb81 100644
--- a/WORKSPACE
+++ b/WORKSPACE
@@ -2,6 +2,7 @@
 
 load("@bazel_tools//tools/build_defs/repo:git.bzl", "new_git_repository")
 load("@bazel_tools//tools/build_defs/repo:http.bzl", "http_archive", "http_file")
+load("@bazel_tools//tools/jdk:remote_java_repository.bzl", "remote_java_repository")
 load(
     "//debian:python.bzl",
     python_debs = "files",
@@ -264,6 +265,7 @@
     "//tools/go:noop_go_toolchain",
     "//tools/rust:rust-toolchain-roborio",
     "//tools/rust:noop_rust_toolchain",
+    "//tools/ts:noop_node_toolchain",
 )
 
 load("//tools/ci:repo_defs.bzl", "ci_configure")
@@ -614,20 +616,19 @@
 )
 
 # Java9 JDK.
-http_archive(
+remote_java_repository(
     name = "openjdk_linux_archive",
-    build_file_content = """
-java_runtime(
-    name = 'jdk',
-    srcs = glob(['**']),
-    visibility = ['//visibility:public'],
-)
-""",
+    exec_compatible_with = [
+        "@platforms//cpu:x86_64",
+        "@platforms//os:linux",
+    ],
+    prefix = "openjdk",
     sha256 = "f27cb933de4f9e7fe9a703486cf44c84bc8e9f138be0c270c9e5716a32367e87",
     strip_prefix = "zulu9.0.7.1-jdk9.0.7-linux_x64-allmodules",
     urls = [
         "https://www.frc971.org/Build-Dependencies/zulu9.0.7.1-jdk9.0.7-linux_x64-allmodules.tar.gz",
     ],
+    version = "9",
 )
 
 local_repository(
@@ -814,14 +815,22 @@
 # I'm sure there is a better path, but that works...
 yarn_install(
     name = "npm",
-    frozen_lockfile = True,
+    frozen_lockfile = False,
     package_json = "//:package.json",
     symlink_node_modules = False,
     yarn_lock = "//:yarn.lock",
 )
 
+load("@build_bazel_rules_nodejs//toolchains/esbuild:esbuild_repositories.bzl", "esbuild_repositories")
+
+esbuild_repositories(npm_repository = "npm")
+
 http_archive(
     name = "io_bazel_rules_webtesting",
+    patch_args = ["-p1"],
+    patches = [
+        "@//third_party:rules_webtesting/rules_webtesting.patch",
+    ],
     sha256 = "e9abb7658b6a129740c0b3ef6f5a2370864e102a5ba5ffca2cea565829ed825a",
     urls = ["https://github.com/bazelbuild/rules_webtesting/releases/download/0.3.5/rules_webtesting.tar.gz"],
 )
@@ -850,6 +859,14 @@
     version = "1.56.1",
 )
 
+load("@io_bazel_rules_webtesting//web:repositories.bzl", "web_test_repositories")
+
+web_test_repositories()
+
+load("@io_bazel_rules_webtesting//web/versioned:browsers-0.3.3.bzl", "browser_repositories")
+
+browser_repositories(chromium = True)
+
 # Flatbuffers
 local_repository(
     name = "com_github_google_flatbuffers",
diff --git a/aos/events/event_loop.h b/aos/events/event_loop.h
index 11368ae..e810e3f 100644
--- a/aos/events/event_loop.h
+++ b/aos/events/event_loop.h
@@ -407,7 +407,9 @@
   // Returns the name of the underlying queue.
   const Channel *channel() const { return sender_->channel(); }
 
+  // TODO(austin): Deprecate the operator bool.
   operator bool() const { return sender_ ? true : false; }
+  bool valid() const { return static_cast<bool>(sender_); }
 
   // Returns the time_points that the last message was sent at.
   aos::monotonic_clock::time_point monotonic_sent_time() const {
diff --git a/aos/events/event_scheduler.cc b/aos/events/event_scheduler.cc
index c06638c..97e0946 100644
--- a/aos/events/event_scheduler.cc
+++ b/aos/events/event_scheduler.cc
@@ -66,20 +66,32 @@
 }
 
 void EventScheduler::RunOnRun() {
-  for (std::function<void()> &on_run : on_run_) {
-    on_run();
+  while (!on_run_.empty()) {
+    std::function<void()> fn = std::move(*on_run_.begin());
+    on_run_.erase(on_run_.begin());
+    fn();
   }
-  on_run_.clear();
 }
 
-void EventScheduler::RunOnStartup() {
-  for (size_t i = 0; i < on_startup_.size(); ++i) {
-    on_startup_[i]();
+void EventScheduler::RunOnStartup() noexcept {
+  while (!on_startup_.empty()) {
+    std::function<void()> fn = std::move(*on_startup_.begin());
+    on_startup_.erase(on_startup_.begin());
+    fn();
   }
-  on_startup_.clear();
 }
 
-void EventScheduler::RunStarted() { started_(); }
+void EventScheduler::RunStarted() {
+  if (started_) {
+    started_();
+  }
+}
+
+void EventScheduler::RunStopped() {
+  if (stopped_) {
+    stopped_();
+  }
+}
 
 std::ostream &operator<<(std::ostream &stream,
                          const aos::distributed_clock::time_point &now) {
@@ -119,6 +131,7 @@
       rebooted.emplace_back(node_index);
       CHECK_EQ(schedulers_[node_index]->boot_count() + 1,
                times[node_index].boot);
+      schedulers_[node_index]->RunStopped();
       schedulers_[node_index]->Shutdown();
     }
   }
@@ -144,6 +157,7 @@
 void EventSchedulerScheduler::RunFor(distributed_clock::duration duration) {
   distributed_clock::time_point end_time = now_ + duration;
   logging::ScopedLogRestorer prev_logger;
+  RunOnStartup();
   RunOnRun();
 
   // Run all the sub-event-schedulers.
@@ -191,10 +205,13 @@
   }
 
   now_ = end_time;
+
+  RunStopped();
 }
 
 void EventSchedulerScheduler::Run() {
   logging::ScopedLogRestorer prev_logger;
+  RunOnStartup();
   RunOnRun();
   // Run all the sub-event-schedulers.
   while (is_running_) {
@@ -232,6 +249,8 @@
   }
 
   is_running_ = false;
+
+  RunStopped();
 }
 
 std::tuple<distributed_clock::time_point, EventScheduler *>
@@ -261,4 +280,17 @@
   return std::make_tuple(min_event_time, min_scheduler);
 }
 
+void EventSchedulerScheduler::TemporarilyStopAndRun(std::function<void()> fn) {
+  const bool was_running = is_running_;
+  if (is_running_) {
+    is_running_ = false;
+    RunStopped();
+  }
+  fn();
+  if (was_running) {
+    RunOnStartup();
+    RunOnRun();
+  }
+}
+
 }  // namespace aos
diff --git a/aos/events/event_scheduler.h b/aos/events/event_scheduler.h
index 55c1cf8..b64728c 100644
--- a/aos/events/event_scheduler.h
+++ b/aos/events/event_scheduler.h
@@ -126,7 +126,12 @@
     started_ = std::move(callback);
   }
 
+  void set_stopped(std::function<void()> callback) {
+    stopped_ = std::move(callback);
+  }
+
   std::function<void()> started_;
+  std::function<void()> stopped_;
   std::function<void()> on_shutdown_;
 
   Token InvalidToken() { return events_list_.end(); }
@@ -138,10 +143,12 @@
   void RunOnRun();
 
   // Runs the OnStartup callbacks.
-  void RunOnStartup();
+  void RunOnStartup() noexcept;
 
   // Runs the Started callback.
   void RunStarted();
+  // Runs the Started callback.
+  void RunStopped();
 
   // Returns true if events are being handled.
   inline bool is_running() const;
@@ -283,6 +290,13 @@
     }
   }
 
+  void RunStopped() {
+    CHECK(!is_running_);
+    for (EventScheduler *scheduler : schedulers_) {
+      scheduler->RunStopped();
+    }
+  }
+
   void SetTimeConverter(TimeConverter *time_converter) {
     time_converter->set_reboot_found(
         [this](distributed_clock::time_point reboot_time,
@@ -294,6 +308,11 @@
         });
   }
 
+  // Runs the provided callback now.  Stops everything, runs the callback, then
+  // starts it all up again.  This lets us do operations like starting and
+  // stopping applications while running.
+  void TemporarilyStopAndRun(std::function<void()> fn);
+
  private:
   // Handles running the OnRun functions.
   void RunOnRun() {
diff --git a/aos/events/logging/BUILD b/aos/events/logging/BUILD
index d190120..ec13f92 100644
--- a/aos/events/logging/BUILD
+++ b/aos/events/logging/BUILD
@@ -134,10 +134,10 @@
     visibility = ["//visibility:public"],
     deps = [
         ":buffer_encoder",
-        ":crc32",
         ":logger_fbs",
         "//aos:configuration_fbs",
         "//aos/containers:resizeable_buffer",
+        "//aos/util:crc32",
         "@com_github_google_flatbuffers//:flatbuffers",
         "@com_github_google_glog//:glog",
         "@com_google_absl//absl/types:span",
@@ -465,12 +465,3 @@
     gen_reflections = 1,
     target_compatible_with = ["@platforms//os:linux"],
 )
-
-cc_library(
-    name = "crc32",
-    srcs = ["crc32.cc"],
-    hdrs = ["crc32.h"],
-    deps = [
-        "@com_google_absl//absl/types:span",
-    ],
-)
diff --git a/aos/events/logging/log_reader.cc b/aos/events/logging/log_reader.cc
index e58ccd2..4e89a0e 100644
--- a/aos/events/logging/log_reader.cc
+++ b/aos/events/logging/log_reader.cc
@@ -39,6 +39,13 @@
     time_estimation_buffer_seconds, 2.0,
     "The time to buffer ahead in the log file to accurately reconstruct time.");
 
+DEFINE_string(
+    start_time, "",
+    "If set, start at this point in time in the log on the realtime clock.");
+DEFINE_string(
+    end_time, "",
+    "If set, end at this point in time in the log on the realtime clock.");
+
 namespace aos {
 namespace configuration {
 // We don't really want to expose this publicly, but log reader doesn't really
@@ -131,6 +138,79 @@
 using message_bridge::RemoteMessage;
 }  // namespace
 
+// Class to manage triggering events on the RT clock while replaying logs. Since
+// the RT clock can only change when we get a message, we only need to update
+// our timers when new messages are read.
+class EventNotifier {
+ public:
+  EventNotifier(EventLoop *event_loop, std::function<void()> fn,
+                std::string_view name,
+                realtime_clock::time_point realtime_event_time)
+      : event_loop_(event_loop),
+        fn_(std::move(fn)),
+        realtime_event_time_(realtime_event_time) {
+    CHECK(event_loop_);
+    event_timer_ = event_loop->AddTimer([this]() { HandleTime(); });
+
+    if (event_loop_->node() != nullptr) {
+      event_timer_->set_name(
+          absl::StrCat(event_loop_->node()->name()->string_view(), "_", name));
+    } else {
+      event_timer_->set_name(name);
+    }
+  }
+
+  ~EventNotifier() { event_timer_->Disable(); }
+
+  // Returns the event trigger time.
+  realtime_clock::time_point realtime_event_time() const {
+    return realtime_event_time_;
+  }
+
+  // Observes the next message and potentially calls the callback or updates the
+  // timer.
+  void ObserveNextMessage(monotonic_clock::time_point monotonic_message_time,
+                          realtime_clock::time_point realtime_message_time) {
+    if (realtime_message_time < realtime_event_time_) {
+      return;
+    }
+    if (called_) {
+      return;
+    }
+
+    // Move the callback wakeup time to the correct time (or make it now if
+    // there's a gap in time) now that we know it is before the next
+    // message.
+    const monotonic_clock::time_point candidate_monotonic =
+        (realtime_event_time_ - realtime_message_time) + monotonic_message_time;
+    const monotonic_clock::time_point monotonic_now =
+        event_loop_->monotonic_now();
+    if (candidate_monotonic < monotonic_now) {
+      // Whops, time went backwards.  Just do it now.
+      HandleTime();
+    } else {
+      event_timer_->Setup(candidate_monotonic);
+    }
+  }
+
+ private:
+  void HandleTime() {
+    if (!called_) {
+      called_ = true;
+      fn_();
+    }
+  }
+
+  EventLoop *event_loop_ = nullptr;
+  TimerHandler *event_timer_ = nullptr;
+  std::function<void()> fn_;
+
+  const realtime_clock::time_point realtime_event_time_ =
+      realtime_clock::min_time;
+
+  bool called_ = false;
+};
+
 LogReader::LogReader(std::string_view filename,
                      const Configuration *replay_configuration)
     : LogReader(SortParts({std::string(filename)}), replay_configuration) {}
@@ -139,6 +219,9 @@
                      const Configuration *replay_configuration)
     : log_files_(std::move(log_files)),
       replay_configuration_(replay_configuration) {
+  SetStartTime(FLAGS_start_time);
+  SetEndTime(FLAGS_end_time);
+
   CHECK_GT(log_files_.size(), 0u);
   {
     // Validate that we have the same config everwhere.  This will be true if
@@ -329,8 +412,15 @@
 
   VLOG(1) << "Starting " << MaybeNodeName(node()) << "at time "
           << monotonic_start_time(boot_count());
-  for (size_t i = 0; i < on_starts_.size(); ++i) {
-    on_starts_[i]();
+  auto fn = [this]() {
+    for (size_t i = 0; i < on_starts_.size(); ++i) {
+      on_starts_[i]();
+    }
+  };
+  if (event_loop_factory_) {
+    event_loop_factory_->AllowApplicationCreationDuring(std::move(fn));
+  } else {
+    fn();
   }
   stopped_ = false;
   started_ = true;
@@ -358,12 +448,19 @@
 void LogReader::State::RunOnEnd() {
   VLOG(1) << "Ending " << MaybeNodeName(node()) << "at time "
           << monotonic_start_time(boot_count());
-  for (size_t i = 0; i < on_ends_.size(); ++i) {
-    on_ends_[i]();
+  auto fn = [this]() {
+    for (size_t i = 0; i < on_ends_.size(); ++i) {
+      on_ends_[i]();
+    }
+  };
+  if (event_loop_factory_) {
+    event_loop_factory_->AllowApplicationCreationDuring(std::move(fn));
+  } else {
+    fn();
   }
 
   stopped_ = true;
-  started_ = false;
+  started_ = true;
 }
 
 void LogReader::Register() {
@@ -397,7 +494,8 @@
         node);
     State *state = states_[node_index].get();
     state->SetNodeEventLoopFactory(
-        event_loop_factory_->GetNodeEventLoopFactory(node));
+        event_loop_factory_->GetNodeEventLoopFactory(node),
+        event_loop_factory_);
 
     state->SetChannelCount(logged_configuration()->channels()->size());
     timestamp_mappers.emplace_back(state->timestamp_mapper());
@@ -489,6 +587,11 @@
 
 void LogReader::Register(SimulatedEventLoopFactory *event_loop_factory) {
   RegisterWithoutStarting(event_loop_factory);
+  StartAfterRegister(event_loop_factory);
+}
+
+void LogReader::StartAfterRegister(
+    SimulatedEventLoopFactory *event_loop_factory) {
   // We want to start the log file at the last start time of the log files
   // from all the nodes.  Compute how long each node's simulation needs to run
   // to move time to this point.
@@ -588,6 +691,10 @@
   State *state =
       states_[configuration::GetNodeIndex(configuration(), node)].get();
 
+  if (!event_loop) {
+    state->ClearTimeFlags();
+  }
+
   state->set_event_loop(event_loop);
 
   // We don't run timing reports when trying to print out logged data, because
@@ -889,7 +996,7 @@
                 << "is on the next boot, " << next_time << " now is "
                 << state->monotonic_now();
         CHECK(event_loop_factory_);
-        state->RunOnEnd();
+        state->NotifyLogfileEnd();
         return;
       }
       VLOG(1) << "Scheduling " << MaybeNodeName(state->event_loop()->node())
@@ -900,7 +1007,7 @@
     } else {
       VLOG(1) << MaybeNodeName(state->event_loop()->node())
               << "No next message, scheduling shutdown";
-      state->RunOnEnd();
+      state->NotifyLogfileEnd();
       // Set a timer up immediately after now to die. If we don't do this,
       // then the senders waiting on the message we just read will never get
       // called.
@@ -917,7 +1024,13 @@
 
   if (state->OldestMessageTime() != BootTimestamp::max_time()) {
     state->set_startup_timer(
-        event_loop->AddTimer([state]() { state->RunOnStart(); }));
+        event_loop->AddTimer([state]() { state->NotifyLogfileStart(); }));
+    if (start_time_ != realtime_clock::min_time) {
+      state->SetStartTimeFlag(start_time_);
+    }
+    if (end_time_ != realtime_clock::max_time) {
+      state->SetEndTimeFlag(end_time_);
+    }
     event_loop->OnRun([state]() {
       BootTimestamp next_time = state->OldestMessageTime();
       CHECK_EQ(next_time.boot, state->boot_count());
@@ -927,6 +1040,40 @@
   }
 }
 
+void LogReader::SetEndTime(std::string end_time) {
+  if (end_time.empty()) {
+    SetEndTime(realtime_clock::max_time);
+  } else {
+    std::optional<aos::realtime_clock::time_point> parsed_end_time =
+        aos::realtime_clock::FromString(end_time);
+    CHECK(parsed_end_time) << ": Failed to parse end time '" << end_time
+                           << "'.  Expected a date in the format of "
+                              "2021-01-15_15-30-35.000000000.";
+    SetEndTime(*parsed_end_time);
+  }
+}
+
+void LogReader::SetEndTime(realtime_clock::time_point end_time) {
+  end_time_ = end_time;
+}
+
+void LogReader::SetStartTime(std::string start_time) {
+  if (start_time.empty()) {
+    SetStartTime(realtime_clock::min_time);
+  } else {
+    std::optional<aos::realtime_clock::time_point> parsed_start_time =
+        aos::realtime_clock::FromString(start_time);
+    CHECK(parsed_start_time) << ": Failed to parse start time '" << start_time
+                             << "'.  Expected a date in the format of "
+                                "2021-01-15_15-30-35.000000000.";
+    SetStartTime(*parsed_start_time);
+  }
+}
+
+void LogReader::SetStartTime(realtime_clock::time_point start_time) {
+  start_time_ = start_time;
+}
+
 void LogReader::Deregister() {
   // Make sure that things get destroyed in the correct order, rather than
   // relying on getting the order correct in the class definition.
@@ -1312,8 +1459,10 @@
 }
 
 void LogReader::State::SetNodeEventLoopFactory(
-    NodeEventLoopFactory *node_event_loop_factory) {
+    NodeEventLoopFactory *node_event_loop_factory,
+    SimulatedEventLoopFactory *event_loop_factory) {
   node_event_loop_factory_ = node_event_loop_factory;
+  event_loop_factory_ = event_loop_factory;
 }
 
 void LogReader::State::SetChannelCount(size_t count) {
@@ -1670,7 +1819,7 @@
   return result;
 }
 
-BootTimestamp LogReader::State::OldestMessageTime() const {
+BootTimestamp LogReader::State::OldestMessageTime() {
   if (timestamp_mapper_ == nullptr) {
     return BootTimestamp::max_time();
   }
@@ -1680,6 +1829,12 @@
   }
   VLOG(2) << MaybeNodeName(node()) << "oldest message at "
           << result_ptr->monotonic_event_time.time;
+
+  if (result_ptr->monotonic_event_time.boot == boot_count()) {
+    ObserveNextMessage(result_ptr->monotonic_event_time.time,
+                       result_ptr->realtime_event_time);
+  }
+
   return result_ptr->monotonic_event_time;
 }
 
@@ -1692,11 +1847,12 @@
 
 void LogReader::State::Deregister() {
   if (started_ && !stopped_) {
-    RunOnEnd();
+    NotifyLogfileEnd();
   }
   for (size_t i = 0; i < channels_.size(); ++i) {
     channels_[i].reset();
   }
+  ClearTimeFlags();
   channel_timestamp_loggers_.clear();
   timestamp_loggers_.clear();
   event_loop_unique_ptr_.reset();
@@ -1705,5 +1861,75 @@
   node_event_loop_factory_ = nullptr;
 }
 
+void LogReader::State::SetStartTimeFlag(realtime_clock::time_point start_time) {
+  if (start_time != realtime_clock::min_time) {
+    start_event_notifier_ = std::make_unique<EventNotifier>(
+        event_loop_, [this]() { NotifyFlagStart(); }, "flag_start", start_time);
+  }
+}
+
+void LogReader::State::SetEndTimeFlag(realtime_clock::time_point end_time) {
+  if (end_time != realtime_clock::max_time) {
+    end_event_notifier_ = std::make_unique<EventNotifier>(
+        event_loop_, [this]() { NotifyFlagEnd(); }, "flag_end", end_time);
+  }
+}
+
+void LogReader::State::ObserveNextMessage(
+    monotonic_clock::time_point monotonic_event,
+    realtime_clock::time_point realtime_event) {
+  if (start_event_notifier_) {
+    start_event_notifier_->ObserveNextMessage(monotonic_event, realtime_event);
+  }
+  if (end_event_notifier_) {
+    end_event_notifier_->ObserveNextMessage(monotonic_event, realtime_event);
+  }
+}
+
+void LogReader::State::ClearTimeFlags() {
+  start_event_notifier_.reset();
+  end_event_notifier_.reset();
+}
+
+void LogReader::State::NotifyLogfileStart() {
+  if (start_event_notifier_) {
+    if (start_event_notifier_->realtime_event_time() >
+        realtime_start_time(boot_count())) {
+      VLOG(1) << "Skipping, " << start_event_notifier_->realtime_event_time()
+              << " > " << realtime_start_time(boot_count());
+      return;
+    }
+  }
+  if (found_last_message_) {
+    VLOG(1) << "Last message already found, bailing";
+    return;
+  }
+  RunOnStart();
+}
+
+void LogReader::State::NotifyFlagStart() {
+  if (start_event_notifier_->realtime_event_time() >=
+      realtime_start_time(boot_count())) {
+    RunOnStart();
+  }
+}
+
+void LogReader::State::NotifyLogfileEnd() {
+  if (found_last_message_) {
+    return;
+  }
+
+  if (!stopped_ && started_) {
+    RunOnEnd();
+  }
+}
+
+void LogReader::State::NotifyFlagEnd() {
+  if (!stopped_ && started_) {
+    RunOnEnd();
+    SetFoundLastMessage(true);
+  }
+}
+
 }  // namespace logger
 }  // namespace aos
diff --git a/aos/events/logging/log_reader.h b/aos/events/logging/log_reader.h
index 3eebba7..9bfc90a 100644
--- a/aos/events/logging/log_reader.h
+++ b/aos/events/logging/log_reader.h
@@ -23,6 +23,8 @@
 namespace aos {
 namespace logger {
 
+class EventNotifier;
+
 // We end up with one of the following 3 log file types.
 //
 // Single node logged as the source node.
@@ -73,10 +75,20 @@
   // below, but can be anything as long as the locations needed to send
   // everything are available.
   void Register(SimulatedEventLoopFactory *event_loop_factory);
+
   // Registers all the callbacks to send the log file data out to an event loop
   // factory.  This does not start replaying or change the current distributed
   // time of the factory.  It does change the monotonic clocks to be right.
   void RegisterWithoutStarting(SimulatedEventLoopFactory *event_loop_factory);
+  // Runs the log until the last start time.  Register above is defined as:
+  // Register(...) {
+  //   RegisterWithoutStarting
+  //   StartAfterRegister
+  // }
+  // This should generally be considered as a stepping stone to convert from
+  // Register() to RegisterWithoutStarting() incrementally.
+  void StartAfterRegister(SimulatedEventLoopFactory *event_loop_factory);
+
   // Creates an SimulatedEventLoopFactory accessible via event_loop_factory(),
   // and then calls Register.
   void Register();
@@ -121,6 +133,14 @@
   realtime_clock::time_point realtime_start_time(
       const Node *node = nullptr) const;
 
+  // Sets the start and end times to replay data until for all nodes.  This
+  // overrides the --start_time and --end_time flags.  The default is to replay
+  // all data.
+  void SetStartTime(std::string start_time);
+  void SetStartTime(realtime_clock::time_point start_time);
+  void SetEndTime(std::string end_time);
+  void SetEndTime(realtime_clock::time_point end_time);
+
   // Causes the logger to publish the provided channel on a different name so
   // that replayed applications can publish on the proper channel name without
   // interference. This operates on raw channel names, without any node or
@@ -277,7 +297,7 @@
     TimestampedMessage PopOldest();
 
     // Returns the monotonic time of the oldest message.
-    BootTimestamp OldestMessageTime() const;
+    BootTimestamp OldestMessageTime();
 
     size_t boot_count() const {
       // If we are replaying directly into an event loop, we can't reboot.  So
@@ -296,7 +316,7 @@
       if (start_time == monotonic_clock::min_time) {
         LOG(ERROR)
             << "No start time, skipping, please figure out when this happens";
-        RunOnStart();
+        NotifyLogfileStart();
         return;
       }
       CHECK_GE(start_time, event_loop_->monotonic_now());
@@ -329,7 +349,9 @@
 
     // Sets the node event loop factory for replaying into a
     // SimulatedEventLoopFactory.  Returns the EventLoop to use.
-    void SetNodeEventLoopFactory(NodeEventLoopFactory *node_event_loop_factory);
+    void SetNodeEventLoopFactory(
+        NodeEventLoopFactory *node_event_loop_factory,
+        SimulatedEventLoopFactory *event_loop_factory);
 
     // Sets and gets the event loop to use.
     void set_event_loop(EventLoop *event_loop) { event_loop_ = event_loop; }
@@ -419,6 +441,18 @@
     void RunOnStart();
     void RunOnEnd();
 
+    // Handles a logfile start event to potentially call the OnStart callbacks.
+    void NotifyLogfileStart();
+    // Handles a start time flag start event to potentially call the OnStart
+    // callbacks.
+    void NotifyFlagStart();
+
+    // Handles a logfile end event to potentially call the OnEnd callbacks.
+    void NotifyLogfileEnd();
+    // Handles a end time flag start event to potentially call the OnEnd
+    // callbacks.
+    void NotifyFlagEnd();
+
     // Unregisters everything so we can destory the event loop.
     // TODO(austin): Is this needed?  OnShutdown should be able to serve this
     // need.
@@ -437,6 +471,18 @@
       }
     }
 
+    // Creates and registers the --start_time and --end_time event callbacks.
+    void SetStartTimeFlag(realtime_clock::time_point start_time);
+    void SetEndTimeFlag(realtime_clock::time_point end_time);
+
+    // Notices the next message to update the start/end time callbacks.
+    void ObserveNextMessage(monotonic_clock::time_point monotonic_event,
+                            realtime_clock::time_point realtime_event);
+
+    // Clears the start and end time flag handlers so we can delete the event
+    // loop.
+    void ClearTimeFlags();
+
     // Sets the next wakeup time on the replay callback.
     void Setup(monotonic_clock::time_point next_time) {
       timer_handler_->Setup(next_time);
@@ -516,6 +562,8 @@
 
     // Factory (if we are in sim) that this loop was created on.
     NodeEventLoopFactory *node_event_loop_factory_ = nullptr;
+    SimulatedEventLoopFactory *event_loop_factory_ = nullptr;
+
     std::unique_ptr<EventLoop> event_loop_unique_ptr_;
     // Event loop.
     const Node *node_ = nullptr;
@@ -524,6 +572,9 @@
     TimerHandler *timer_handler_ = nullptr;
     TimerHandler *startup_timer_ = nullptr;
 
+    std::unique_ptr<EventNotifier> start_event_notifier_;
+    std::unique_ptr<EventNotifier> end_event_notifier_;
+
     // Filters (or nullptr if it isn't a forwarded channel) for each channel.
     // This corresponds to the object which is shared among all the channels
     // going between 2 nodes.  The second element in the tuple indicates if this
@@ -598,6 +649,9 @@
 
   // Whether to exit the SimulatedEventLoop when we finish reading the logs.
   bool exit_on_finish_ = true;
+
+  realtime_clock::time_point start_time_ = realtime_clock::min_time;
+  realtime_clock::time_point end_time_ = realtime_clock::max_time;
 };
 
 }  // namespace logger
diff --git a/aos/events/logging/logger_test.cc b/aos/events/logging/logger_test.cc
index 1732549..3b0b672 100644
--- a/aos/events/logging/logger_test.cc
+++ b/aos/events/logging/logger_test.cc
@@ -523,7 +523,12 @@
   }
 };
 
-void ConfirmReadable(const std::vector<std::string> &files) {
+std::vector<std::pair<std::vector<realtime_clock::time_point>,
+                      std::vector<realtime_clock::time_point>>>
+ConfirmReadable(
+    const std::vector<std::string> &files,
+    realtime_clock::time_point start_time = realtime_clock::min_time,
+    realtime_clock::time_point end_time = realtime_clock::max_time) {
   {
     LogReader reader(SortParts(files));
 
@@ -535,22 +540,65 @@
     reader.Deregister();
   }
   {
+    std::vector<std::pair<std::vector<realtime_clock::time_point>,
+                          std::vector<realtime_clock::time_point>>>
+        result;
     LogReader reader(SortParts(files));
 
+    reader.SetStartTime(start_time);
+    reader.SetEndTime(end_time);
+
     SimulatedEventLoopFactory log_reader_factory(reader.configuration());
     reader.RegisterWithoutStarting(&log_reader_factory);
+    result.resize(
+        configuration::NodesCount(log_reader_factory.configuration()));
     if (configuration::MultiNode(log_reader_factory.configuration())) {
+      size_t i = 0;
       for (const aos::Node *node :
            *log_reader_factory.configuration()->nodes()) {
-        reader.OnStart(node, [node]() {
+        LOG(INFO) << "Registering start";
+        reader.OnStart(node, [node, &log_reader_factory, &result,
+                              node_index = i]() {
           LOG(INFO) << "Starting " << node->name()->string_view();
+          result[node_index].first.push_back(
+              log_reader_factory.GetNodeEventLoopFactory(node)->realtime_now());
         });
+        reader.OnEnd(node, [node, &log_reader_factory, &result,
+                            node_index = i]() {
+          LOG(INFO) << "Ending " << node->name()->string_view();
+          result[node_index].second.push_back(
+              log_reader_factory.GetNodeEventLoopFactory(node)->realtime_now());
+        });
+        ++i;
       }
+    } else {
+      reader.OnStart([&log_reader_factory, &result]() {
+        LOG(INFO) << "Starting";
+        result[0].first.push_back(
+            log_reader_factory.GetNodeEventLoopFactory(nullptr)
+                ->realtime_now());
+      });
+      reader.OnEnd([&log_reader_factory, &result]() {
+        LOG(INFO) << "Ending";
+        result[0].second.push_back(
+            log_reader_factory.GetNodeEventLoopFactory(nullptr)
+                ->realtime_now());
+      });
     }
 
     log_reader_factory.Run();
 
     reader.Deregister();
+
+    for (auto x : result) {
+      for (auto y : x.first) {
+        VLOG(1) << "Start " << y;
+      }
+      for (auto y : x.second) {
+        VLOG(1) << "End " << y;
+      }
+    }
+    return result;
   }
 }
 
@@ -3589,7 +3637,27 @@
   // Confirm that we can parse the result.  LogReader has enough internal CHECKs
   // to confirm the right thing happened.
   const std::vector<LogFile> sorted_parts = SortParts(filenames);
-  ConfirmReadable(filenames);
+  auto result = ConfirmReadable(filenames);
+  EXPECT_THAT(result[0].first, ::testing::ElementsAre(realtime_clock::epoch() +
+                                                      chrono::seconds(1)));
+  EXPECT_THAT(result[0].second,
+              ::testing::ElementsAre(realtime_clock::epoch() +
+                                     chrono::microseconds(34990350)));
+
+  EXPECT_THAT(result[1].first,
+              ::testing::ElementsAre(
+                  realtime_clock::epoch() + chrono::seconds(1),
+                  realtime_clock::epoch() + chrono::microseconds(3323000)));
+  EXPECT_THAT(result[1].second,
+              ::testing::ElementsAre(
+                  realtime_clock::epoch() + chrono::microseconds(13990200),
+                  realtime_clock::epoch() + chrono::microseconds(16313200)));
+
+  EXPECT_THAT(result[2].first, ::testing::ElementsAre(realtime_clock::epoch() +
+                                                      chrono::seconds(1)));
+  EXPECT_THAT(result[2].second,
+              ::testing::ElementsAre(realtime_clock::epoch() +
+                                     chrono::microseconds(34900150)));
 }
 
 // Tests that local data before remote data after reboot is properly replayed.
@@ -3730,9 +3798,201 @@
   // Confirm that we can parse the result.  LogReader has enough internal CHECKs
   // to confirm the right thing happened.
   const std::vector<LogFile> sorted_parts = SortParts(filenames);
-  ConfirmReadable(filenames);
+  auto result = ConfirmReadable(filenames);
+
+  EXPECT_THAT(result[0].first, ::testing::ElementsAre(realtime_clock::epoch()));
+  EXPECT_THAT(result[0].second,
+              ::testing::ElementsAre(realtime_clock::epoch() +
+                                     chrono::microseconds(11000350)));
+
+  EXPECT_THAT(result[1].first,
+              ::testing::ElementsAre(
+                  realtime_clock::epoch(),
+                  realtime_clock::epoch() + chrono::microseconds(107005000)));
+  EXPECT_THAT(result[1].second,
+              ::testing::ElementsAre(
+                  realtime_clock::epoch() + chrono::microseconds(4000150),
+                  realtime_clock::epoch() + chrono::microseconds(111000200)));
+
+  EXPECT_THAT(result[2].first, ::testing::ElementsAre(realtime_clock::epoch()));
+  EXPECT_THAT(result[2].second,
+              ::testing::ElementsAre(realtime_clock::epoch() +
+                                     chrono::microseconds(11000150)));
+
+  auto start_stop_result = ConfirmReadable(
+      filenames, realtime_clock::epoch() + chrono::milliseconds(2000),
+      realtime_clock::epoch() + chrono::milliseconds(3000));
+
+  EXPECT_THAT(start_stop_result[0].first, ::testing::ElementsAre(realtime_clock::epoch() +
+                                                      chrono::seconds(2)));
+  EXPECT_THAT(start_stop_result[0].second, ::testing::ElementsAre(realtime_clock::epoch() +
+                                                       chrono::seconds(3)));
+  EXPECT_THAT(start_stop_result[1].first, ::testing::ElementsAre(realtime_clock::epoch() +
+                                                      chrono::seconds(2)));
+  EXPECT_THAT(start_stop_result[1].second, ::testing::ElementsAre(realtime_clock::epoch() +
+                                                       chrono::seconds(3)));
+  EXPECT_THAT(start_stop_result[2].first, ::testing::ElementsAre(realtime_clock::epoch() +
+                                                      chrono::seconds(2)));
+  EXPECT_THAT(start_stop_result[2].second, ::testing::ElementsAre(realtime_clock::epoch() +
+                                                       chrono::seconds(3)));
 }
 
+// Tests that setting the start and stop flags across a reboot works as
+// expected.
+TEST(MultinodeRebootLoggerTest, RebootStartStopTimes) {
+  aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+      aos::configuration::ReadConfig(ArtifactPath(
+          "aos/events/logging/multinode_pingpong_split3_config.json"));
+  message_bridge::TestingTimeConverter time_converter(
+      configuration::NodesCount(&config.message()));
+  SimulatedEventLoopFactory event_loop_factory(&config.message());
+  event_loop_factory.SetTimeConverter(&time_converter);
+  NodeEventLoopFactory *const pi1 =
+      event_loop_factory.GetNodeEventLoopFactory("pi1");
+  const size_t pi1_index = configuration::GetNodeIndex(
+      event_loop_factory.configuration(), pi1->node());
+  NodeEventLoopFactory *const pi2 =
+      event_loop_factory.GetNodeEventLoopFactory("pi2");
+  const size_t pi2_index = configuration::GetNodeIndex(
+      event_loop_factory.configuration(), pi2->node());
+  NodeEventLoopFactory *const pi3 =
+      event_loop_factory.GetNodeEventLoopFactory("pi3");
+  const size_t pi3_index = configuration::GetNodeIndex(
+      event_loop_factory.configuration(), pi3->node());
+
+  const std::string kLogfile1_1 =
+      aos::testing::TestTmpDir() + "/multi_logfile1/";
+  const std::string kLogfile2_1 =
+      aos::testing::TestTmpDir() + "/multi_logfile2.1/";
+  const std::string kLogfile2_2 =
+      aos::testing::TestTmpDir() + "/multi_logfile2.2/";
+  const std::string kLogfile3_1 =
+      aos::testing::TestTmpDir() + "/multi_logfile3/";
+  util::UnlinkRecursive(kLogfile1_1);
+  util::UnlinkRecursive(kLogfile2_1);
+  util::UnlinkRecursive(kLogfile2_2);
+  util::UnlinkRecursive(kLogfile3_1);
+  {
+    CHECK_EQ(pi1_index, 0u);
+    CHECK_EQ(pi2_index, 1u);
+    CHECK_EQ(pi3_index, 2u);
+
+    time_converter.AddNextTimestamp(
+        distributed_clock::epoch(),
+        {BootTimestamp::epoch(), BootTimestamp::epoch(),
+         BootTimestamp::epoch()});
+    const chrono::nanoseconds reboot_time = chrono::milliseconds(5000);
+    time_converter.AddNextTimestamp(
+        distributed_clock::epoch() + reboot_time,
+        {BootTimestamp::epoch() + reboot_time,
+         BootTimestamp{.boot = 1,
+                       .time = monotonic_clock::epoch() + reboot_time},
+         BootTimestamp::epoch() + reboot_time});
+  }
+
+  std::vector<std::string> filenames;
+  {
+    LoggerState pi1_logger = LoggerState::MakeLogger(
+        pi1, &event_loop_factory, SupportedCompressionAlgorithms()[0]);
+    LoggerState pi3_logger = LoggerState::MakeLogger(
+        pi3, &event_loop_factory, SupportedCompressionAlgorithms()[0]);
+    {
+      // And now start the logger.
+      LoggerState pi2_logger = LoggerState::MakeLogger(
+          pi2, &event_loop_factory, SupportedCompressionAlgorithms()[0]);
+
+      pi1_logger.StartLogger(kLogfile1_1);
+      pi3_logger.StartLogger(kLogfile3_1);
+      pi2_logger.StartLogger(kLogfile2_1);
+
+      event_loop_factory.RunFor(chrono::milliseconds(1005));
+
+      // Now that we've got a start time in the past, turn on data.
+      std::unique_ptr<aos::EventLoop> ping_event_loop =
+          pi1->MakeEventLoop("ping");
+      Ping ping(ping_event_loop.get());
+
+      pi2->AlwaysStart<Pong>("pong");
+
+      event_loop_factory.RunFor(chrono::milliseconds(3000));
+
+      pi2_logger.AppendAllFilenames(&filenames);
+    }
+    event_loop_factory.RunFor(chrono::milliseconds(995));
+    // pi2 now reboots at 5 seconds.
+    {
+      event_loop_factory.RunFor(chrono::milliseconds(1000));
+
+      // Make local stuff happen before we start logging and connect the remote.
+      pi2->AlwaysStart<Pong>("pong");
+      std::unique_ptr<aos::EventLoop> ping_event_loop =
+          pi1->MakeEventLoop("ping");
+      Ping ping(ping_event_loop.get());
+      event_loop_factory.RunFor(chrono::milliseconds(5));
+
+      // Start logging again on pi2 after it is up.
+      LoggerState pi2_logger = LoggerState::MakeLogger(
+          pi2, &event_loop_factory, SupportedCompressionAlgorithms()[0]);
+      pi2_logger.StartLogger(kLogfile2_2);
+
+      event_loop_factory.RunFor(chrono::milliseconds(5000));
+
+      pi2_logger.AppendAllFilenames(&filenames);
+    }
+
+    pi1_logger.AppendAllFilenames(&filenames);
+    pi3_logger.AppendAllFilenames(&filenames);
+  }
+
+  const std::vector<LogFile> sorted_parts = SortParts(filenames);
+  auto result = ConfirmReadable(filenames);
+
+  EXPECT_THAT(result[0].first, ::testing::ElementsAre(realtime_clock::epoch()));
+  EXPECT_THAT(result[0].second,
+              ::testing::ElementsAre(realtime_clock::epoch() +
+                                     chrono::microseconds(11000350)));
+
+  EXPECT_THAT(result[1].first,
+              ::testing::ElementsAre(
+                  realtime_clock::epoch(),
+                  realtime_clock::epoch() + chrono::microseconds(6005000)));
+  EXPECT_THAT(result[1].second,
+              ::testing::ElementsAre(
+                  realtime_clock::epoch() + chrono::microseconds(4900150),
+                  realtime_clock::epoch() + chrono::microseconds(11000200)));
+
+  EXPECT_THAT(result[2].first, ::testing::ElementsAre(realtime_clock::epoch()));
+  EXPECT_THAT(result[2].second,
+              ::testing::ElementsAre(realtime_clock::epoch() +
+                                     chrono::microseconds(11000150)));
+
+  // Confirm we observed the correct start and stop times.  We should see the
+  // reboot here.
+  auto start_stop_result = ConfirmReadable(
+      filenames, realtime_clock::epoch() + chrono::milliseconds(2000),
+      realtime_clock::epoch() + chrono::milliseconds(8000));
+
+  EXPECT_THAT(
+      start_stop_result[0].first,
+      ::testing::ElementsAre(realtime_clock::epoch() + chrono::seconds(2)));
+  EXPECT_THAT(
+      start_stop_result[0].second,
+      ::testing::ElementsAre(realtime_clock::epoch() + chrono::seconds(8)));
+  EXPECT_THAT(start_stop_result[1].first,
+              ::testing::ElementsAre(
+                  realtime_clock::epoch() + chrono::seconds(2),
+                  realtime_clock::epoch() + chrono::microseconds(6005000)));
+  EXPECT_THAT(start_stop_result[1].second,
+              ::testing::ElementsAre(
+                  realtime_clock::epoch() + chrono::microseconds(4900150),
+                  realtime_clock::epoch() + chrono::seconds(8)));
+  EXPECT_THAT(
+      start_stop_result[2].first,
+      ::testing::ElementsAre(realtime_clock::epoch() + chrono::seconds(2)));
+  EXPECT_THAT(
+      start_stop_result[2].second,
+      ::testing::ElementsAre(realtime_clock::epoch() + chrono::seconds(8)));
+}
 
 }  // namespace testing
 }  // namespace logger
diff --git a/aos/events/logging/snappy_encoder.cc b/aos/events/logging/snappy_encoder.cc
index 4621273..8f46cf3 100644
--- a/aos/events/logging/snappy_encoder.cc
+++ b/aos/events/logging/snappy_encoder.cc
@@ -1,6 +1,6 @@
 #include "aos/events/logging/snappy_encoder.h"
 
-#include "aos/events/logging/crc32.h"
+#include "aos/util/crc32.h"
 #include "external/snappy/snappy.h"
 
 namespace aos::logger {
diff --git a/aos/events/simulated_event_loop.cc b/aos/events/simulated_event_loop.cc
index a2428a4..a1ef95d 100644
--- a/aos/events/simulated_event_loop.cc
+++ b/aos/events/simulated_event_loop.cc
@@ -1268,6 +1268,11 @@
       event_loop->SetIsRunning(true);
     }
   });
+  scheduler_.set_stopped([this]() {
+    for (SimulatedEventLoop *event_loop : event_loops_) {
+      event_loop->SetIsRunning(false);
+    }
+  });
   scheduler_.set_on_shutdown([this]() {
     VLOG(1) << scheduler_.distributed_now() << " " << NodeName(this->node())
             << monotonic_now() << " Shutting down node.";
@@ -1339,7 +1344,7 @@
 
 void NodeEventLoopFactory::Shutdown() {
   for (SimulatedEventLoop *event_loop : event_loops_) {
-    event_loop->SetIsRunning(false);
+    CHECK(!event_loop->is_running());
   }
 
   CHECK(started_);
@@ -1367,12 +1372,11 @@
 
 void SimulatedEventLoopFactory::RunFor(monotonic_clock::duration duration) {
   // This sets running to true too.
-  scheduler_scheduler_.RunOnStartup();
   scheduler_scheduler_.RunFor(duration);
   for (std::unique_ptr<NodeEventLoopFactory> &node : node_factories_) {
     if (node) {
       for (SimulatedEventLoop *loop : node->event_loops_) {
-        loop->SetIsRunning(false);
+        CHECK(!loop->is_running());
       }
     }
   }
@@ -1380,12 +1384,11 @@
 
 void SimulatedEventLoopFactory::Run() {
   // This sets running to true too.
-  scheduler_scheduler_.RunOnStartup();
   scheduler_scheduler_.Run();
   for (std::unique_ptr<NodeEventLoopFactory> &node : node_factories_) {
     if (node) {
       for (SimulatedEventLoop *loop : node->event_loops_) {
-        loop->SetIsRunning(false);
+        CHECK(!loop->is_running());
       }
     }
   }
@@ -1458,6 +1461,11 @@
   return std::move(result);
 }
 
+void SimulatedEventLoopFactory::AllowApplicationCreationDuring(
+    std::function<void()> fn) {
+  scheduler_scheduler_.TemporarilyStopAndRun(std::move(fn));
+}
+
 void NodeEventLoopFactory::Disconnect(const Node *other) {
   factory_->bridge_->Disconnect(node_, other);
 }
diff --git a/aos/events/simulated_event_loop.h b/aos/events/simulated_event_loop.h
index bd589d6..9a447e9 100644
--- a/aos/events/simulated_event_loop.h
+++ b/aos/events/simulated_event_loop.h
@@ -128,6 +128,11 @@
   // tests.
   void SkipTimingReport();
 
+  // Re-enables application creation for the duration of fn.  This is mostly to
+  // allow use cases like log reading to create applications after the node
+  // starts up without stopping execution.
+  void AllowApplicationCreationDuring(std::function<void()> fn);
+
  private:
   friend class NodeEventLoopFactory;
 
diff --git a/aos/events/simulated_event_loop_test.cc b/aos/events/simulated_event_loop_test.cc
index a94b895..09202ff 100644
--- a/aos/events/simulated_event_loop_test.cc
+++ b/aos/events/simulated_event_loop_test.cc
@@ -181,6 +181,29 @@
   EXPECT_EQ(counter, 0);
 }
 
+// Test that TemporarilyStopAndRun respects and preserves running.
+TEST(EventSchedulerTest, TemporarilyStopAndRun) {
+  int counter = 0;
+  EventSchedulerScheduler scheduler_scheduler;
+  EventScheduler scheduler(0);
+  scheduler_scheduler.AddEventScheduler(&scheduler);
+
+  scheduler_scheduler.TemporarilyStopAndRun(
+      [&]() { CHECK(!scheduler_scheduler.is_running()); });
+  ASSERT_FALSE(scheduler_scheduler.is_running());
+
+  FunctionEvent e([&]() {
+    counter += 1;
+    CHECK(scheduler_scheduler.is_running());
+    scheduler_scheduler.TemporarilyStopAndRun(
+        [&]() { CHECK(!scheduler_scheduler.is_running()); });
+    CHECK(scheduler_scheduler.is_running());
+  });
+  scheduler.Schedule(monotonic_clock::epoch() + chrono::seconds(1), &e);
+  scheduler_scheduler.Run();
+  EXPECT_EQ(counter, 1);
+}
+
 void SendTestMessage(aos::Sender<TestMessage> *sender, int value) {
   aos::Sender<TestMessage>::Builder builder = sender->MakeBuilder();
   TestMessage::Builder test_message_builder =
diff --git a/aos/events/simulated_network_bridge.cc b/aos/events/simulated_network_bridge.cc
index 4c9208e..c6ea811 100644
--- a/aos/events/simulated_network_bridge.cc
+++ b/aos/events/simulated_network_bridge.cc
@@ -228,6 +228,8 @@
 
       // TODO(austin): Not cool.  We want to actually forward these.  This means
       // we need a more sophisticated concept of what is running.
+      // TODO(james): This fails if multiple messages are sent on the same channel
+      // within the same callback.
       LOG(WARNING) << "Not forwarding message on "
                    << configuration::CleanedChannelToString(fetcher_->channel())
                    << " because we aren't running.  Set at "
diff --git a/aos/network/log_web_proxy_main.cc b/aos/network/log_web_proxy_main.cc
index 5c099a2..945d034 100644
--- a/aos/network/log_web_proxy_main.cc
+++ b/aos/network/log_web_proxy_main.cc
@@ -42,7 +42,8 @@
 
   event_loop->SkipTimingReport();
 
-  aos::web_proxy::WebProxy web_proxy(event_loop.get(), FLAGS_buffer_size);
+  aos::web_proxy::WebProxy web_proxy(
+      event_loop.get(), aos::web_proxy::StoreHistory::kYes, FLAGS_buffer_size);
 
   web_proxy.SetDataPath(FLAGS_data_dir.c_str());
 
diff --git a/aos/network/rawrtc.cc b/aos/network/rawrtc.cc
index 98f2448..c195a4b 100644
--- a/aos/network/rawrtc.cc
+++ b/aos/network/rawrtc.cc
@@ -148,8 +148,9 @@
 
 void ScopedDataChannel::Close() {
   CHECK(opened_);
-  CHECK(!closed_);
-  CHECK_RAWRTC(rawrtc_data_channel_close(data_channel_));
+  if (!closed_) {
+    CHECK_RAWRTC(rawrtc_data_channel_close(data_channel_));
+  }
 }
 
 void ScopedDataChannel::Send(const ::flatbuffers::DetachedBuffer &buffer) {
diff --git a/aos/network/web_proxy.cc b/aos/network/web_proxy.cc
index fdd8f1e..6d4f23f 100644
--- a/aos/network/web_proxy.cc
+++ b/aos/network/web_proxy.cc
@@ -28,7 +28,9 @@
 namespace aos {
 namespace web_proxy {
 WebsocketHandler::WebsocketHandler(::seasocks::Server *server,
-                                   aos::EventLoop *event_loop, int buffer_size)
+                                   aos::EventLoop *event_loop,
+                                   StoreHistory store_history,
+                                   int per_channel_buffer_size_bytes)
     : server_(server),
       config_(aos::CopyFlatBuffer(event_loop->configuration())),
       event_loop_(event_loop) {
@@ -47,7 +49,10 @@
     if (aos::configuration::ChannelIsReadableOnNode(channel, self)) {
       auto fetcher = event_loop_->MakeRawFetcher(channel);
       subscribers_.emplace_back(std::make_unique<aos::web_proxy::Subscriber>(
-          std::move(fetcher), i, buffer_size));
+          std::move(fetcher), i, store_history,
+          per_channel_buffer_size_bytes < 0
+              ? -1
+              : per_channel_buffer_size_bytes / channel->max_size()));
     } else {
       subscribers_.emplace_back(nullptr);
     }
@@ -126,19 +131,24 @@
   global_epoll->DeleteFd(fd);
 }
 
-WebProxy::WebProxy(aos::EventLoop *event_loop, int buffer_size)
-    : WebProxy(event_loop, &internal_epoll_, buffer_size) {}
+WebProxy::WebProxy(aos::EventLoop *event_loop, StoreHistory store_history,
+                   int per_channel_buffer_size_bytes)
+    : WebProxy(event_loop, &internal_epoll_, store_history,
+               per_channel_buffer_size_bytes) {}
 
-WebProxy::WebProxy(aos::ShmEventLoop *event_loop, int buffer_size)
-    : WebProxy(event_loop, event_loop->epoll(), buffer_size) {}
+WebProxy::WebProxy(aos::ShmEventLoop *event_loop, StoreHistory store_history,
+                   int per_channel_buffer_size_bytes)
+    : WebProxy(event_loop, event_loop->epoll(), store_history,
+               per_channel_buffer_size_bytes) {}
 
 WebProxy::WebProxy(aos::EventLoop *event_loop, aos::internal::EPoll *epoll,
-                   int buffer_size)
+                   StoreHistory store_history,
+                   int per_channel_buffer_size_bytes)
     : epoll_(epoll),
       server_(std::make_shared<aos::seasocks::SeasocksLogger>(
           ::seasocks::Logger::Level::Info)),
-      websocket_handler_(
-          new WebsocketHandler(&server_, event_loop, buffer_size)) {
+      websocket_handler_(new WebsocketHandler(
+          &server_, event_loop, store_history, per_channel_buffer_size_bytes)) {
   CHECK(!global_epoll);
   global_epoll = epoll;
 
@@ -192,10 +202,13 @@
 }
 
 void Subscriber::RunIteration() {
-  if (channels_.empty() && buffer_size_ == 0) {
+  if (channels_.empty() && (buffer_size_ == 0 || !store_history_)) {
+    fetcher_->Fetch();
+    message_buffer_.clear();
     return;
   }
 
+
   while (fetcher_->FetchNext()) {
     // If we aren't building up a buffer, short-circuit the FetchNext().
     if (buffer_size_ == 0) {
@@ -271,12 +284,6 @@
   ChannelInformation info;
   info.transfer_method = transfer_method;
 
-  // If we aren't keeping a buffer and there are no existing listeners, call
-  // Fetch() to avoid falling behind on future calls to FetchNext().
-  if (channels_.empty() && buffer_size_ == 0) {
-    fetcher_->Fetch();
-  }
-
   channels_.emplace_back(std::make_pair(data_channel, info));
 
   data_channel->set_on_message(
diff --git a/aos/network/web_proxy.fbs b/aos/network/web_proxy.fbs
index 6c85acb..f1d6645 100644
--- a/aos/network/web_proxy.fbs
+++ b/aos/network/web_proxy.fbs
@@ -64,7 +64,7 @@
 
 enum TransferMethod : byte {
   SUBSAMPLE,
-  EVERYTHING_WITH_HISTORY,
+  LOSSLESS,
 }
 
 table ChannelRequest {
diff --git a/aos/network/web_proxy.h b/aos/network/web_proxy.h
index 0815ebf..baca26e 100644
--- a/aos/network/web_proxy.h
+++ b/aos/network/web_proxy.h
@@ -24,13 +24,19 @@
 class Subscriber;
 class ApplicationConnection;
 
+enum class StoreHistory {
+  kNo,
+  kYes,
+};
+
 // Basic class that handles receiving new websocket connections. Creates a new
 // Connection to manage the rest of the negotiation and data passing. When the
 // websocket closes, it deletes the Connection.
 class WebsocketHandler : public ::seasocks::WebSocket::Handler {
  public:
   WebsocketHandler(::seasocks::Server *server, aos::EventLoop *event_loop,
-                   int buffer_size);
+                   StoreHistory store_history,
+                   int per_channel_buffer_size_bytes);
   void onConnect(::seasocks::WebSocket *sock) override;
   void onData(::seasocks::WebSocket *sock, const uint8_t *data,
               size_t size) override;
@@ -50,15 +56,28 @@
 // Wrapper class that manages the seasocks server and WebsocketHandler.
 class WebProxy {
  public:
-  WebProxy(aos::EventLoop *event_loop, int buffer_size);
-  WebProxy(aos::ShmEventLoop *event_loop, int buffer_size);
+  // Constructs a WebProxy object for interacting with a webpage. store_history
+  // and per_channel_buffer_size_bytes specify how we manage delivering LOSSLESS
+  // messages to the client:
+  // * store_history specifies whether we should always buffer up data for all
+  //   channels--even for messages that are played prior to the client
+  //   connecting. This is mostly useful for log replay where the client
+  //   will typically connect after the logfile has been fully loaded/replayed.
+  // * per_channel_buffer_size_bytes is the maximum amount of data to buffer
+  //   up per channel (-1 will indicate infinite data, which is used during log
+  //   replay). This is divided by the max_size per channel to determine
+  //   how many messages to queue up.
+  WebProxy(aos::EventLoop *event_loop, StoreHistory store_history,
+           int per_channel_buffer_size_bytes);
+  WebProxy(aos::ShmEventLoop *event_loop, StoreHistory store_history,
+           int per_channel_buffer_size_bytes);
   ~WebProxy();
 
   void SetDataPath(const char *path) { server_.setStaticPath(path); }
 
  private:
   WebProxy(aos::EventLoop *event_loop, aos::internal::EPoll *epoll,
-           int buffer_size);
+           StoreHistory store_history, int per_channel_buffer_size_bytes);
 
   aos::internal::EPoll internal_epoll_;
   aos::internal::EPoll *const epoll_;
@@ -96,9 +115,10 @@
 class Subscriber {
  public:
   Subscriber(std::unique_ptr<RawFetcher> fetcher, int channel_index,
-             int buffer_size)
+             StoreHistory store_history, int buffer_size)
       : fetcher_(std::move(fetcher)),
         channel_index_(channel_index),
+        store_history_(store_history == StoreHistory::kYes),
         buffer_size_(buffer_size) {}
 
   void RunIteration();
@@ -133,6 +153,10 @@
 
   std::unique_ptr<RawFetcher> fetcher_;
   int channel_index_;
+  // If set, will always build up a buffer of the most recent buffer_size_
+  // messages. If store_history_ is *not* set we will only buffer up messages
+  // while there is an active listener.
+  bool store_history_;
   int buffer_size_;
   std::deque<Message> message_buffer_;
   // The ScopedDataChannel that we use for actually sending data over WebRTC
diff --git a/aos/network/web_proxy_main.cc b/aos/network/web_proxy_main.cc
index 06fe942..f3ad926 100644
--- a/aos/network/web_proxy_main.cc
+++ b/aos/network/web_proxy_main.cc
@@ -6,7 +6,9 @@
 
 DEFINE_string(config, "./config.json", "File path of aos configuration");
 DEFINE_string(data_dir, "www", "Directory to serve data files from");
-DEFINE_int32(buffer_size, 0, "-1 if infinite, in # of messages / channel.");
+DEFINE_int32(buffer_size, 1000000,
+             "-1 if infinite, in bytes / channel. If there are no active "
+             "connections, will not store anything.");
 
 int main(int argc, char **argv) {
   aos::InitGoogle(&argc, &argv);
@@ -16,7 +18,8 @@
 
   aos::ShmEventLoop event_loop(&config.message());
 
-  aos::web_proxy::WebProxy web_proxy(&event_loop, FLAGS_buffer_size);
+  aos::web_proxy::WebProxy web_proxy(
+      &event_loop, aos::web_proxy::StoreHistory::kNo, FLAGS_buffer_size);
   web_proxy.SetDataPath(FLAGS_data_dir.c_str());
 
   event_loop.Run();
diff --git a/aos/network/www/proxy.ts b/aos/network/www/proxy.ts
index 5461899..5415400 100644
--- a/aos/network/www/proxy.ts
+++ b/aos/network/www/proxy.ts
@@ -117,7 +117,7 @@
       name: string, type: string,
       handler: (data: Uint8Array, sentTime: number) => void): void {
     this.addHandlerImpl(
-        name, type, TransferMethod.EVERYTHING_WITH_HISTORY, handler);
+        name, type, TransferMethod.LOSSLESS, handler);
   }
 
   /**
@@ -137,7 +137,7 @@
     if (!this.handlerFuncs.has(channel.key())) {
       this.handlerFuncs.set(channel.key(), []);
     } else {
-      if (method == TransferMethod.EVERYTHING_WITH_HISTORY) {
+      if (method == TransferMethod.LOSSLESS) {
         console.warn(
             'Behavior of multiple reliable handlers is currently poorly ' +
             'defined and may not actually deliver all of the messages.');
diff --git a/aos/starter/starter.sh b/aos/starter/starter.sh
index 7a25fc7..f18dfda 100755
--- a/aos/starter/starter.sh
+++ b/aos/starter/starter.sh
@@ -8,6 +8,43 @@
   ln -s /var/local/natinst/log/FRC_UserProgram.log /tmp/FRC_UserProgram.log
   ln -s /var/local/natinst/log/FRC_UserProgram.log "${ROBOT_CODE}/FRC_UserProgram.log"
 elif [[ "$(hostname)" == "pi-"* ]]; then
+  function chrtirq() {
+    ps -ef | grep "\\[$1\\]" | awk '{print $2}' | xargs chrt $2 -p $3
+  }
+
+  chrtirq "irq/20-fe00b880" -f 50
+  chrtirq "irq/66-xhci_hcd" -f 1
+  chrtirq "irq/50-VCHIQ do" -o 0
+  chrtirq "irq/27-DMA IRQ" -f 50
+  chrtirq "irq/51-mmc1" -o 0
+  chrtirq "irq/51-mmc0" -o 0
+  chrtirq "irq/51-s-mmc0" -o 0
+  chrtirq "irq/64-v3d" -o 0
+  chrtirq "irq/24-vc4 hvs" -o 0
+  chrtirq "irq/42-vc4 hdmi" -o 0
+  chrtirq "irq/43-vc4 hdmi" -o 0
+  chrtirq "irq/39-vc4 hdmi" -o 0
+  chrtirq "irq/39-s-vc4 hd" -o 0
+  chrtirq "irq/38-vc4 hdmi" -o 0
+  chrtirq "irq/38-s-vc4 hd" -o 0
+  chrtirq "irq/29-DMA IRQ" -f 50
+  chrtirq "irq/48-vc4 hdmi" -o 0
+  chrtirq "irq/49-vc4 hdmi" -o 0
+  chrtirq "irq/45-vc4 hdmi" -o 0
+  chrtirq "irq/45-s-vc4 hd" -o 0
+  chrtirq "irq/44-vc4 hdmi" -o 0
+  chrtirq "irq/44-s-vc4 hd" -o 0
+  chrtirq "irq/30-DMA IRQ" -f 50
+  chrtirq "irq/19-fe004000" -f 50
+  chrtirq "irq/34-vc4 crtc" -o 0
+  chrtirq "irq/35-vc4 crtc" -o 0
+  chrtirq "irq/36-vc4 crtc" -o 0
+  chrtirq "irq/35-vc4 crtc" -o 0
+  chrtirq "irq/37-vc4 crtc" -o 0
+  chrtirq "irq/23-uart-pl0" -o 0
+  chrtirq "irq/57-eth0" -f 10
+  chrtirq "irq/58-eth0" -f 10
+
   # We have systemd configured to handle restarting, so just exec.
   export PATH="${PATH}:/home/pi/robot_code"
   rm -rf /dev/shm/aos
diff --git a/aos/util/BUILD b/aos/util/BUILD
index 0314069..8df16e2 100644
--- a/aos/util/BUILD
+++ b/aos/util/BUILD
@@ -257,6 +257,15 @@
     ],
 )
 
+cc_library(
+    name = "crc32",
+    srcs = ["crc32.cc"],
+    hdrs = ["crc32.h"],
+    deps = [
+        "@com_google_absl//absl/types:span",
+    ],
+)
+
 py_library(
     name = "python_init",
     srcs = ["__init__.py"],
diff --git a/aos/events/logging/crc32.cc b/aos/util/crc32.cc
similarity index 95%
rename from aos/events/logging/crc32.cc
rename to aos/util/crc32.cc
index cd9d9fb..7f13f30 100644
--- a/aos/events/logging/crc32.cc
+++ b/aos/util/crc32.cc
@@ -1,4 +1,4 @@
-#include "aos/events/logging/crc32.h"
+#include "aos/util/crc32.h"
 
 namespace aos {
 
@@ -53,9 +53,8 @@
   return AccumulateCrc32(data, std::nullopt);
 }
 
-uint32_t AccumulateCrc32(
-    const absl::Span<uint8_t> data,
-    std::optional<uint32_t> current_checksum) {
+uint32_t AccumulateCrc32(const absl::Span<uint8_t> data,
+                         std::optional<uint32_t> current_checksum) {
   uint32_t crc =
       current_checksum.has_value() ? current_checksum.value() : 0xFF'FF'FF'FF;
   for (const uint8_t n : data) {
diff --git a/aos/events/logging/crc32.h b/aos/util/crc32.h
similarity index 100%
rename from aos/events/logging/crc32.h
rename to aos/util/crc32.h
diff --git a/build_tests/BUILD b/build_tests/BUILD
index 6a81509..705c4ff 100644
--- a/build_tests/BUILD
+++ b/build_tests/BUILD
@@ -1,8 +1,10 @@
 load("@com_google_protobuf//:protobuf.bzl", "cc_proto_library")
-load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_py_library")
+load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_go_library", "flatbuffer_py_library")
 load("@io_bazel_rules_go//go:def.bzl", "go_binary", "go_library")
 load("//tools/build_rules:apache.bzl", "apache_wrapper")
 load("@rules_rust//rust:defs.bzl", "rust_binary", "rust_library", "rust_test")
+load("@npm//@bazel/typescript:index.bzl", "ts_library")
+load("@npm//@bazel/concatjs:index.bzl", "karma_web_test_suite")
 
 cc_test(
     name = "gflags_build_test",
@@ -77,6 +79,14 @@
     visibility = ["//visibility:public"],
 )
 
+flatbuffer_go_library(
+    name = "test_go_fbs",
+    srcs = ["test.fbs"],
+    importpath = "github.com/frc971/971-Robot-Code/build_tests/fbs",
+    target_compatible_with = ["@platforms//cpu:x86_64"],
+    visibility = ["//visibility:public"],
+)
+
 py_test(
     name = "python_fbs",
     srcs = ["python_fbs.py"],
@@ -147,3 +157,25 @@
     target_compatible_with = ["@platforms//os:linux"],
     deps = [":hello_lib"],
 )
+
+ts_library(
+    name = "build_tests_ts",
+    srcs = ["basic.ts"],
+)
+
+ts_library(
+    name = "ts_test",
+    testonly = True,
+    srcs = ["basic_test.ts"],
+    deps = [
+        ":build_tests_ts",
+        "@npm//@types/jasmine",
+    ],
+)
+
+karma_web_test_suite(
+    name = "karma",
+    testonly = True,
+    target_compatible_with = ["@platforms//os:linux"],
+    deps = [":ts_test"],
+)
diff --git a/build_tests/basic.ts b/build_tests/basic.ts
new file mode 100644
index 0000000..6ddac49
--- /dev/null
+++ b/build_tests/basic.ts
@@ -0,0 +1,6 @@
+/**
+ * Computes the sum of the input values
+ */
+export function add(x: number, y: number): number {
+  return x + y;
+}
diff --git a/build_tests/basic_test.ts b/build_tests/basic_test.ts
new file mode 100644
index 0000000..298f928
--- /dev/null
+++ b/build_tests/basic_test.ts
@@ -0,0 +1,11 @@
+import {add} from './basic';
+
+describe('add', () => {
+  it('should sum numbers', () => {
+    expect(3 + 4).toEqual(7);
+  });
+
+  it('should not sum numbers', () => {
+    expect(add(3, 3)).not.toEqual(7);
+  });
+});
diff --git a/build_tests/go_flatbuffer/BUILD b/build_tests/go_flatbuffer/BUILD
new file mode 100644
index 0000000..d472a6f
--- /dev/null
+++ b/build_tests/go_flatbuffer/BUILD
@@ -0,0 +1,20 @@
+load("@io_bazel_rules_go//go:def.bzl", "go_binary", "go_library")
+
+go_library(
+    name = "go_flatbuffer_lib",
+    srcs = ["go_fbs.go"],
+    importpath = "github.com/frc971/971-Robot-Code/build_tests/go_flatbuffer",
+    target_compatible_with = ["@platforms//cpu:x86_64"],
+    visibility = ["//visibility:private"],
+    deps = [
+        "//build_tests:test_go_fbs",
+        "@com_github_google_flatbuffers//go:go_default_library",
+    ],
+)
+
+go_binary(
+    name = "go_flatbuffer",
+    embed = [":go_flatbuffer_lib"],
+    target_compatible_with = ["@platforms//cpu:x86_64"],
+    visibility = ["//visibility:public"],
+)
diff --git a/build_tests/go_flatbuffer/go_fbs.go b/build_tests/go_flatbuffer/go_fbs.go
new file mode 100644
index 0000000..2e936c1
--- /dev/null
+++ b/build_tests/go_flatbuffer/go_fbs.go
@@ -0,0 +1,13 @@
+package main
+
+import (
+	build_tests "github.com/frc971/971-Robot-Code/build_tests/fbs"
+	flatbuffers "github.com/google/flatbuffers/go"
+)
+
+func main() {
+	builder := flatbuffers.NewBuilder(1024)
+	build_tests.FooStart(builder)
+	build_tests.FooAddValue(builder, 3)
+	build_tests.FooEnd(builder)
+}
diff --git a/frc971/analysis/BUILD b/frc971/analysis/BUILD
index d846ce3..82f397c 100644
--- a/frc971/analysis/BUILD
+++ b/frc971/analysis/BUILD
@@ -52,6 +52,7 @@
         "//y2020/control_loops/superstructure:hood_plotter",
         "//y2020/control_loops/superstructure:turret_plotter",
         "//y2021_bot3/control_loops/superstructure:superstructure_plotter",
+        "//y2022/control_loops/localizer:localizer_plotter",
     ],
 )
 
diff --git a/frc971/analysis/in_process_plotter.cc b/frc971/analysis/in_process_plotter.cc
index 0eaf719..cd52b1c 100644
--- a/frc971/analysis/in_process_plotter.cc
+++ b/frc971/analysis/in_process_plotter.cc
@@ -15,7 +15,7 @@
       event_loop_factory_(&config_.message()),
       event_loop_(event_loop_factory_.MakeEventLoop("plotter")),
       plot_sender_(event_loop_->MakeSender<Plot>("/analysis")),
-      web_proxy_(event_loop_.get(), -1),
+      web_proxy_(event_loop_.get(), aos::web_proxy::StoreHistory::kYes, -1),
       builder_(plot_sender_.MakeBuilder()) {
   web_proxy_.SetDataPath(kDataPath);
   event_loop_->SkipTimingReport();
diff --git a/frc971/analysis/live_web_plotter_demo.sh b/frc971/analysis/live_web_plotter_demo.sh
index 4c4c9c4..45f3b92 100755
--- a/frc971/analysis/live_web_plotter_demo.sh
+++ b/frc971/analysis/live_web_plotter_demo.sh
@@ -1 +1 @@
-./aos/network/web_proxy_main --config=aos/network/www/test_config.json --data_dir=frc971/analysis
+./aos/network/web_proxy_main --config=aos/network/www/test_config.json --data_dir=frc971/analysis "$@"
diff --git a/frc971/analysis/plot_index.ts b/frc971/analysis/plot_index.ts
index 2df65f6..a5203b0 100644
--- a/frc971/analysis/plot_index.ts
+++ b/frc971/analysis/plot_index.ts
@@ -32,8 +32,10 @@
     'org_frc971/y2020/control_loops/superstructure/finisher_plotter'
 import {plotTurret} from
     'org_frc971/y2020/control_loops/superstructure/turret_plotter'
-import {plotLocalizer} from
+import {plotLocalizer as plot2020Localizer} from
     'org_frc971/y2020/control_loops/drivetrain/localizer_plotter'
+import {plotLocalizer as plot2022Localizer} from
+    'org_frc971/y2022/control_loops/localizer/localizer_plotter'
 import {plotAccelerator} from
     'org_frc971/y2020/control_loops/superstructure/accelerator_plotter'
 import {plotHood} from
@@ -104,7 +106,8 @@
   ['Accelerator', new PlotState(plotDiv, plotAccelerator)],
   ['Hood', new PlotState(plotDiv, plotHood)],
   ['Turret', new PlotState(plotDiv, plotTurret)],
-  ['2020 Localizer', new PlotState(plotDiv, plotLocalizer)],
+  ['2022 Localizer', new PlotState(plotDiv, plot2022Localizer)],
+  ['2020 Localizer', new PlotState(plotDiv, plot2020Localizer)],
   ['C++ Plotter', new PlotState(plotDiv, plotData)],
   ['Y2021 3rd Robot Superstructure', new PlotState(plotDiv, plotSuperstructure)],
 ]);
@@ -154,4 +157,4 @@
   plotSelect.value = getDefaultPlot();
   // Force the event to occur once at the start.
   plotSelect.dispatchEvent(new Event('input'));
-});
\ No newline at end of file
+});
diff --git a/frc971/control_loops/drivetrain/drivetrain.cc b/frc971/control_loops/drivetrain/drivetrain.cc
index 62b77c4..66a3dcd 100644
--- a/frc971/control_loops/drivetrain/drivetrain.cc
+++ b/frc971/control_loops/drivetrain/drivetrain.cc
@@ -35,7 +35,7 @@
       localizer_control_fetcher_(
           event_loop->MakeFetcher<LocalizerControl>("/drivetrain")),
       imu_values_fetcher_(
-          event_loop->MakeFetcher<::frc971::IMUValuesBatch>("/drivetrain")),
+          event_loop->TryMakeFetcher<::frc971::IMUValuesBatch>("/drivetrain")),
       gyro_reading_fetcher_(
           event_loop->MakeFetcher<::frc971::sensors::GyroReading>(
               "/drivetrain")),
@@ -52,7 +52,9 @@
   event_loop->OnRun([this]() {
     // On the first fetch, make sure that we are caught all the way up to the
     // present.
-    imu_values_fetcher_.Fetch();
+    if (imu_values_fetcher_.valid()) {
+      imu_values_fetcher_.Fetch();
+    }
   });
   if (dt_config.is_simulated) {
     down_estimator_.assume_perfect_gravity();
@@ -117,7 +119,7 @@
       break;
   }
 
-  while (imu_values_fetcher_.FetchNext()) {
+  while (imu_values_fetcher_.valid() && imu_values_fetcher_.FetchNext()) {
     CHECK(imu_values_fetcher_->has_readings());
     last_gyro_time_ = monotonic_now;
     for (const IMUValues *value : *imu_values_fetcher_->readings()) {
@@ -138,7 +140,7 @@
   }
 
   bool got_imu_reading = false;
-  if (imu_values_fetcher_.get() != nullptr) {
+  if (imu_values_fetcher_.valid() && imu_values_fetcher_.get() != nullptr) {
     imu_zeroer_.ProcessMeasurements();
     got_imu_reading = true;
     CHECK(imu_values_fetcher_->has_readings());
@@ -202,7 +204,9 @@
       break;
   }
 
-  ready_ = imu_zeroer_.Zeroed();
+  ready_ = dt_config_.gyro_type == GyroType::SPARTAN_GYRO ||
+           dt_config_.gyro_type == GyroType::FLIPPED_SPARTAN_GYRO ||
+           imu_zeroer_.Zeroed();
 
   // TODO(james): How aggressively can we fault here? If we fault to
   // aggressively, we might have issues during startup if wpilib_interface takes
@@ -211,11 +215,18 @@
     last_gyro_rate_ = 0.0;
   }
 
-  localizer_->Update(
-      {last_last_voltage_(kLeftVoltage), last_last_voltage_(kRightVoltage)},
-      monotonic_now, position->left_encoder(), position->right_encoder(),
-      down_estimator_.avg_recent_yaw_rates(),
-      down_estimator_.avg_recent_accel());
+  if (imu_values_fetcher_.valid()) {
+    localizer_->Update(
+        {last_last_voltage_(kLeftVoltage), last_last_voltage_(kRightVoltage)},
+        monotonic_now, position->left_encoder(), position->right_encoder(),
+        down_estimator_.avg_recent_yaw_rates(),
+        down_estimator_.avg_recent_accel());
+  } else {
+    localizer_->Update(
+        {last_last_voltage_(kLeftVoltage), last_last_voltage_(kRightVoltage)},
+        monotonic_now, position->left_encoder(), position->right_encoder(),
+        last_gyro_rate_, Eigen::Vector3d::Zero());
+  }
 
   // If we get a new message setting the absolute position, then reset the
   // localizer.
diff --git a/frc971/control_loops/drivetrain/drivetrain_test_lib.cc b/frc971/control_loops/drivetrain/drivetrain_test_lib.cc
index 4b5138e..a973552 100644
--- a/frc971/control_loops/drivetrain/drivetrain_test_lib.cc
+++ b/frc971/control_loops/drivetrain/drivetrain_test_lib.cc
@@ -93,16 +93,20 @@
 }
 
 DrivetrainSimulation::DrivetrainSimulation(
-    ::aos::EventLoop *event_loop, const DrivetrainConfig<double> &dt_config)
+    ::aos::EventLoop *event_loop, ::aos::EventLoop *imu_event_loop,
+    const DrivetrainConfig<double> &dt_config,
+    aos::monotonic_clock::duration imu_read_period)
     : event_loop_(event_loop),
+      imu_event_loop_(imu_event_loop),
       robot_state_fetcher_(event_loop_->MakeFetcher<::aos::RobotState>("/aos")),
       drivetrain_position_sender_(
           event_loop_
               ->MakeSender<::frc971::control_loops::drivetrain::Position>(
                   "/drivetrain")),
       drivetrain_truth_sender_(
-          event_loop_->MakeSender<::frc971::control_loops::drivetrain::Status>(
-              "/drivetrain/truth")),
+          event_loop_
+              ->TryMakeSender<::frc971::control_loops::drivetrain::Status>(
+                  "/drivetrain/truth")),
       drivetrain_output_fetcher_(
           event_loop_->MakeFetcher<::frc971::control_loops::drivetrain::Output>(
               "/drivetrain")),
@@ -110,7 +114,7 @@
           event_loop_->MakeFetcher<::frc971::control_loops::drivetrain::Status>(
               "/drivetrain")),
       imu_sender_(
-          event_loop->MakeSender<::frc971::IMUValuesBatch>("/drivetrain")),
+          event_loop->TryMakeSender<::frc971::IMUValuesBatch>("/drivetrain")),
       dt_config_(dt_config),
       drivetrain_plant_(MakePlantFromConfig(dt_config_)),
       velocity_drivetrain_(
@@ -121,6 +125,14 @@
                                     StateFeedbackHybridPlant<2, 2, 2>,
                                     HybridKalman<2, 2, 2>>(
                   dt_config_.make_hybrid_drivetrain_velocity_loop()))) {
+  if (imu_event_loop_ != nullptr) {
+    CHECK(!imu_sender_);
+    imu_sender_ =
+        imu_event_loop_->MakeSender<::frc971::IMUValuesBatch>("/localizer");
+    gyro_sender_ =
+        event_loop_->MakeSender<::frc971::sensors::GyroReading>("/drivetrain");
+  }
+  CHECK(imu_sender_);
   Reinitialize();
   last_U_.setZero();
   event_loop_->AddPhasedLoop(
@@ -147,9 +159,7 @@
         SendImuMessage();
       },
       dt_config_.dt);
-  // TODO(milind): We should be able to get IMU readings at 1 kHz instead of 2.
-  event_loop_->AddPhasedLoop([this](int) { ReadImu(); },
-                             frc971::controls::kLoopFrequency);
+  event_loop_->AddPhasedLoop([this](int) { ReadImu(); }, imu_read_period);
 }
 
 void DrivetrainSimulation::Reinitialize() {
@@ -163,6 +173,9 @@
 }
 
 void DrivetrainSimulation::SendTruthMessage() {
+  if (!drivetrain_truth_sender_) {
+    return;
+  }
   auto builder = drivetrain_truth_sender_.MakeBuilder();
   auto status_builder =
       builder.MakeBuilder<frc971::control_loops::drivetrain::Status>();
@@ -178,15 +191,16 @@
   const double right_encoder = GetRightPosition();
 
   if (send_messages_) {
-    ::aos::Sender<::frc971::control_loops::drivetrain::Position>::Builder
-        builder = drivetrain_position_sender_.MakeBuilder();
-    frc971::control_loops::drivetrain::Position::Builder position_builder =
-        builder.MakeBuilder<frc971::control_loops::drivetrain::Position>();
+    flatbuffers::FlatBufferBuilder fbb;
+    frc971::control_loops::drivetrain::Position::Builder position_builder(fbb);
     position_builder.add_left_encoder(left_encoder);
     position_builder.add_right_encoder(right_encoder);
     position_builder.add_left_shifter_position(left_gear_high_ ? 1.0 : 0.0);
     position_builder.add_right_shifter_position(right_gear_high_ ? 1.0 : 0.0);
-    CHECK_EQ(builder.Send(position_builder.Finish()),
+    fbb.Finish(position_builder.Finish());
+    aos::FlatbufferDetachedBuffer<frc971::control_loops::drivetrain::Position>
+        position(fbb.Release());
+    CHECK_EQ(drivetrain_position_sender_.Send(position),
              aos::RawSender::Error::kOk);
   }
 }
@@ -204,17 +218,19 @@
                           (dt_config_.robot_radius * 2.0));
 
   // Acceleration due to gravity, in m/s/s.
-  constexpr double kG = 9.807;
+  constexpr double kG = 9.80665;
   const Eigen::Vector3d accel =
       dt_config_.imu_transform.inverse() *
       Eigen::Vector3d(last_acceleration_.x() / kG, last_acceleration_.y() / kG,
-                      1.0);
+                      last_acceleration_.z() + 1.0);
   const int64_t timestamp =
       std::chrono::duration_cast<std::chrono::nanoseconds>(
           event_loop_->monotonic_now().time_since_epoch())
           .count();
+  last_yaw_rate_ = gyro.z();
   imu_readings_.push({.gyro = gyro,
                       .accel = accel,
+                      .encoders = {GetLeftPosition(), GetRightPosition()},
                       .timestamp = timestamp,
                       .faulted = imu_faulted_});
 }
@@ -224,16 +240,15 @@
     return;
   }
 
+  flatbuffers::FlatBufferBuilder fbb;
   std::vector<flatbuffers::Offset<IMUValues>> imu_values;
-  auto builder = imu_sender_.MakeBuilder();
 
   // Send all the IMU readings and pop the ones we have sent
   while (!imu_readings_.empty()) {
     const auto imu_reading = imu_readings_.front();
     imu_readings_.pop();
 
-    frc971::ADIS16470DiagStat::Builder diag_stat_builder =
-        builder.MakeBuilder<frc971::ADIS16470DiagStat>();
+    frc971::ADIS16470DiagStat::Builder diag_stat_builder(fbb);
     diag_stat_builder.add_clock_error(false);
     diag_stat_builder.add_memory_failure(imu_reading.faulted);
     diag_stat_builder.add_sensor_failure(false);
@@ -244,8 +259,7 @@
 
     const auto diag_stat_offset = diag_stat_builder.Finish();
 
-    frc971::IMUValues::Builder imu_builder =
-        builder.MakeBuilder<frc971::IMUValues>();
+    frc971::IMUValues::Builder imu_builder(fbb);
     imu_builder.add_self_test_diag_stat(diag_stat_offset);
 
     imu_builder.add_gyro_x(imu_reading.gyro.x());
@@ -257,17 +271,34 @@
     imu_builder.add_accelerometer_z(imu_reading.accel.z());
     imu_builder.add_monotonic_timestamp_ns(imu_reading.timestamp);
 
+    if (imu_event_loop_ != nullptr) {
+      imu_builder.add_pico_timestamp_us(imu_reading.timestamp / 1000);
+      imu_builder.add_data_counter(imu_data_counter_++);
+      imu_builder.add_checksum_failed(false);
+      imu_builder.add_left_encoder(imu_reading.encoders(0));
+      imu_builder.add_right_encoder(imu_reading.encoders(1));
+    }
+
     imu_values.push_back(imu_builder.Finish());
   }
 
   flatbuffers::Offset<
       flatbuffers::Vector<flatbuffers::Offset<frc971::IMUValues>>>
-      imu_values_offset = builder.fbb()->CreateVector(imu_values);
-  frc971::IMUValuesBatch::Builder imu_values_batch_builder =
-      builder.MakeBuilder<frc971::IMUValuesBatch>();
+      imu_values_offset = fbb.CreateVector(imu_values);
+  frc971::IMUValuesBatch::Builder imu_values_batch_builder(fbb);
   imu_values_batch_builder.add_readings(imu_values_offset);
-  CHECK_EQ(builder.Send(imu_values_batch_builder.Finish()),
-           aos::RawSender::Error::kOk);
+  fbb.Finish(imu_values_batch_builder.Finish());
+  aos::FlatbufferDetachedBuffer<frc971::IMUValuesBatch> message = fbb.Release();
+  CHECK_EQ(imu_sender_.Send(message), aos::RawSender::Error::kOk);
+  if (gyro_sender_) {
+    auto builder = gyro_sender_.MakeBuilder();
+    sensors::GyroReading::Builder reading_builder =
+        builder.MakeBuilder<sensors::GyroReading>();
+    reading_builder.add_angle(state_(2));
+    reading_builder.add_velocity(last_yaw_rate_);
+    CHECK_EQ(builder.Send(reading_builder.Finish()),
+             aos::RawSender::Error::kOk);
+  }
 }
 
 // Simulates the drivetrain moving for one timestep.
@@ -331,6 +362,12 @@
   // TODO(james): Allow inputting arbitrary calibrations, e.g., for testing
   // situations where the IMU is not perfectly flat in the CG of the robot.
   last_acceleration_ << (Xdot(3, 0) + Xdot(4, 0)) / 2.0, centripetal_accel, 0.0;
+  double accel_disturbance =
+      std::sin(10.0 * 2 * M_PI *
+               aos::time::DurationInSeconds(
+                   event_loop_->monotonic_now().time_since_epoch())) *
+      accel_sin_wave_magnitude_;
+  last_acceleration_.z() += accel_disturbance;
 }
 
 void DrivetrainSimulation::MaybePlot() {
diff --git a/frc971/control_loops/drivetrain/drivetrain_test_lib.h b/frc971/control_loops/drivetrain/drivetrain_test_lib.h
index b98711b..356eadf 100644
--- a/frc971/control_loops/drivetrain/drivetrain_test_lib.h
+++ b/frc971/control_loops/drivetrain/drivetrain_test_lib.h
@@ -13,6 +13,7 @@
 #include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
 #include "frc971/control_loops/state_feedback_loop.h"
 #include "frc971/wpilib/imu_batch_generated.h"
+#include "frc971/queues/gyro_generated.h"
 
 namespace frc971 {
 namespace control_loops {
@@ -50,7 +51,13 @@
   // Constructs a motor simulation.
   // TODO(aschuh) Do we want to test the clutch one too?
   DrivetrainSimulation(::aos::EventLoop *event_loop,
-                       const DrivetrainConfig<double> &dt_config);
+                       ::aos::EventLoop *imu_event_loop,
+                       const DrivetrainConfig<double> &dt_config,
+                       aos::monotonic_clock::duration imu_read_period =
+                           frc971::controls::kLoopFrequency);
+  DrivetrainSimulation(::aos::EventLoop *event_loop,
+                       const DrivetrainConfig<double> &dt_config)
+      : DrivetrainSimulation(event_loop, nullptr, dt_config) {}
 
   // Resets the plant.
   void Reinitialize();
@@ -87,11 +94,17 @@
   }
 
   void set_imu_faulted(const bool fault_imu) { imu_faulted_ = fault_imu; }
+  void set_accel_sin_magnitude(double magnitude) {
+    accel_sin_wave_magnitude_ = magnitude;
+  }
 
  private:
   struct ImuReading {
     Eigen::Vector3d gyro;
     Eigen::Vector3d accel;
+    // On the 2022 robot, encoders are read as part of the same procedure that
+    // reads the IMU.
+    Eigen::Vector2d encoders;
     int64_t timestamp;
     bool faulted;
   };
@@ -109,6 +122,7 @@
   void Simulate();
 
   ::aos::EventLoop *event_loop_;
+  ::aos::EventLoop *imu_event_loop_;
   ::aos::Fetcher<::aos::RobotState> robot_state_fetcher_;
 
   ::aos::Sender<::frc971::control_loops::drivetrain::Position>
@@ -120,9 +134,12 @@
   ::aos::Fetcher<::frc971::control_loops::drivetrain::Status>
       drivetrain_status_fetcher_;
   ::aos::Sender<::frc971::IMUValuesBatch> imu_sender_;
+  ::aos::Sender<::frc971::sensors::GyroReading> gyro_sender_;
 
   bool imu_faulted_ = false;
 
+  double last_yaw_rate_ = 0.0;
+  int imu_data_counter_ = 0;
   std::queue<ImuReading> imu_readings_;
 
   DrivetrainConfig<double> dt_config_;
@@ -153,6 +170,8 @@
   ::std::vector<double> trajectory_y_;
 
   bool send_messages_ = true;
+  // Magnitude of sine wave to feed into the measured accelerations.
+  double accel_sin_wave_magnitude_ = 0.0;
 };
 
 }  // namespace testing
diff --git a/frc971/control_loops/python/angular_system.py b/frc971/control_loops/python/angular_system.py
index cad3221..df6c0f6 100755
--- a/frc971/control_loops/python/angular_system.py
+++ b/frc971/control_loops/python/angular_system.py
@@ -20,6 +20,7 @@
                  kalman_q_vel,
                  kalman_q_voltage,
                  kalman_r_position,
+                 radius = None,
                  dt=0.00505):
         """Constructs an AngularSystemParams object.
 
@@ -38,6 +39,7 @@
         self.kalman_q_vel = kalman_q_vel
         self.kalman_q_voltage = kalman_q_voltage
         self.kalman_r_position = kalman_r_position
+        self.radius = radius
         self.dt = dt
 
 
@@ -80,11 +82,17 @@
         glog.debug('Controllability of %d',
                    numpy.linalg.matrix_rank(controllability))
         glog.debug('J: %f', self.J)
-        glog.debug('Stall torque: %f', self.motor.stall_torque / self.G)
-        glog.debug('Stall acceleration: %f',
+        glog.debug('Stall torque: %f (N m)', self.motor.stall_torque / self.G)
+        if self.params.radius is not None:
+            glog.debug('Stall force: %f (N)',
+                       self.motor.stall_torque / self.G / self.params.radius)
+            glog.debug('Stall force: %f (lbf)',
+                       self.motor.stall_torque / self.G / self.params.radius * 0.224809)
+
+        glog.debug('Stall acceleration: %f (rad/s^2)',
                    self.motor.stall_torque / self.G / self.J)
 
-        glog.debug('Free speed is %f',
+        glog.debug('Free speed is %f (rad/s)',
                    -self.B_continuous[1, 0] / self.A_continuous[1, 1] * 12.0)
 
         self.Q = numpy.matrix([[(1.0 / (self.params.q_pos**2.0)), 0.0],
diff --git a/frc971/imu/ADIS16505.cc b/frc971/imu/ADIS16505.cc
index 4c31cab..9ed77a9 100644
--- a/frc971/imu/ADIS16505.cc
+++ b/frc971/imu/ADIS16505.cc
@@ -196,6 +196,10 @@
 void maybe_send_pi_packet();
 
 void gpio_irq_handler(uint gpio, uint32_t events) {
+  if (gpio == SYNC_IMU && (events & GPIO_IRQ_EDGE_RISE)) {
+    // Grab a timestamp for when the data sample was actually collected.
+    data_collect_timestamp = time_us_32();
+  }
   if (gpio == DR_IMU && (events & GPIO_IRQ_EDGE_RISE)) {
     data_ready();
   }
@@ -321,9 +325,6 @@
 }
 
 void data_ready() {
-  // save timestamp
-  data_collect_timestamp = time_us_32();
-
   // read encoders
   quadrature_encoder_request_count(pio0, 0);
   quadrature_encoder_request_count(pio0, 1);
@@ -377,7 +378,12 @@
     pwm_set_gpio_level(RATE_PWM, rate_level);
 
     // 0 to 360
-    uint16_t heading_level = (int16_t)(fmod(yaw, 360) / 360.0 * PWM_TOP);
+    double wrapped_heading = fmod(yaw, 360);
+    if (wrapped_heading < 0) {
+      wrapped_heading = wrapped_heading + 360;
+    }
+
+    uint16_t heading_level = (int16_t)(wrapped_heading / 360.0 * PWM_TOP);
     pwm_set_gpio_level(HEADING_PWM, heading_level);
   }
 
@@ -456,7 +462,10 @@
 }
 
 void setup_adis16505() {
+  // Disable the interrupts from the data-ready/sync pins to avoid interrupts
+  // while attempting to reset the IMU.
   gpio_set_irq_enabled(DR_IMU, GPIO_IRQ_EDGE_RISE, false);
+  gpio_set_irq_enabled(SYNC_IMU, GPIO_IRQ_EDGE_RISE, false);
 
   while (true) {
     adis16505_reset();
@@ -509,8 +518,8 @@
           (0u << 8) /* send gyro and accelerometer data in burst mode */ |
           (1u << 7) /* enable gyro linear g compensation */ |
           (1u << 6) /* enable point of percussion alignment */ |
-          (0u << 2) /* internal clock mode */ |
-          (0u << 1) /* sync polarity, doesn't matter */ |
+          (11u << 2) /* output sync mode (uses internal 2kHz clock) */ |
+          (1u << 1) /* sync polarity, active high */ |
           (1u << 0) /* data ready is active high */);
   // Rate of the output will be 2000 / (DEC_RATE + 1) Hz.
   write_register(DEC_RATE, 0 /* no decimation */);
@@ -519,6 +528,7 @@
 
   imu_reset_count++;
 
+  gpio_set_irq_enabled(SYNC_IMU, GPIO_IRQ_EDGE_RISE, true);
   gpio_set_irq_enabled_with_callback(DR_IMU, GPIO_IRQ_EDGE_RISE, true,
                                      &gpio_irq_handler);
 }
@@ -626,13 +636,21 @@
   irq_set_enabled(DMA_IRQ_1, true);
 
   /* All IRQ priorities are initialized to PICO_DEFAULT_IRQ_PRIORITY by the pico
-   * runtime at startup.
+   * runtime at startup. As such, their priorities will correspond to their
+   * IRQ numbers (See Table 80 in the rp2040 datasheet). The interrupts are
+   * listed highest priority to lowest below--i.e., the sync/data ready
+   * interrupts are currently at the lowest priority.
+   * TODO(james): In the nominal case, the GPIO interrupts should never
+   * interfere with the SPI data transfer, but we may still want to up the
+   * GPIO priority using irq_set_priority() so that we are guaranteed good
+   * timestamps.
    *
    * Handler             | Interrupt    | Cause of interrupt
    * --------------------|--------------|---------------------------------------
    * imu_read_finished   | DMA_IRQ_0    | When the dma read from the imu is done
    * pi_transfer_finished| DMA_IRQ_1    | When the dma read to the pi is
    * done data_ready     | IO_IRQ_BANK0 | On the rising edge of DR_IMU
+   * sync pin high       | IO_IRQ_BANK0 | On the rising edge of SYNC_IMU
    */
 
   // Tell the GPIOs they are allocated to PWM
diff --git a/frc971/raspi/rootfs/README.md b/frc971/raspi/rootfs/README.md
index a9c7251..b972038 100644
--- a/frc971/raspi/rootfs/README.md
+++ b/frc971/raspi/rootfs/README.md
@@ -1,3 +1,5 @@
+# Creating an SD card to run the Raspberry Pis
+
 This modifies a stock debian root filesystem to be able to operate as a vision
 pi.  It is not trying to be reproducible, but should be good enough for FRC
 purposes.
@@ -5,15 +7,37 @@
 The default hostname and IP is pi-971-1, 10.9.71.101.
   Username pi, password raspberry.
 
-Download 2021-10-30-raspios-bullseye-armhf-lite.img (or any newer
-bullseye version, as a .zip file) from
-`https://www.raspberrypi.org/downloads/raspberry-pi-os/`, extract
-(unzip) the .img file, and edit `modify_rootfs.sh` to point to it.
+## Build the real-time kernel using `build_kernel.sh`
 
-Run modify_rootfs.sh to build the filesystem (you might need to hit
+- Checkout the real-time kernel source code, e.g.,
+  `cd CODE_DIR`
+  `git clone git@github.com:frc971/linux.git`
+  `git checkout frc971-5.10-pi4-rt branch`
+
+- Run `build_kernel.sh` to compile the real-time kernel
+  `cd ROOTFS_DIR` (where ROOTFS_DIR -> //frc971/raspi/rootfs)
+  `./build_kernel.sh CODE_DIR/linux kernel_5.10.tar.gz`
+
+## Download the Raspberry Pi OS
+
+Download the appropriate Raspberry Pi OS image, e.g.,
+`2022-01-28-raspios-bullseye-arm64-lite.img` (or any newer arm64
+bullseye version, as a .zip file) from
+`https://www.raspberrypi.org/downloads/raspberry-pi-os/`, and extract
+(unzip) the .img file.
+
+## Create our custom OS image using `modify_root.sh`
+
+- Edit `modify_rootfs.sh` to point to the kernel file (e.g.,
+`KERNEL=kernel_5.10.tar.gz`) and the Raspberry Pi OS image (e.g.,
+`IMAGE=2022-01-28-raspios-bullseye-arm64-lite.img`)
+
+- Run modify_rootfs.sh to build the filesystem (you might need to hit
 return in a spot or two and will need sudo privileges to mount the
 partition):
-  * `modify_root.sh`
+  * `./modify_root.sh`
+
+## Write the file system to the SD card
 
 VERY IMPORTANT NOTE: Before doing the next step, use `lsblk` to find
 the device and make absolutely sure this isn't your hard drive or
@@ -45,6 +69,6 @@
   * Download the code:
     Once this is completed, you can boot the pi with the newly flashed SD
     card, and download the code to the pi using:
-      `bazel run -c opt --cpu=armv7 //y2022:pi_download_stripped -- PI_IP_ADDR
+      `bazel run -c opt --config=armv7 //y2022:pi_download_stripped -- PI_IP_ADDR
 
     where PI_IP_ADDR is the IP address of the target pi, e.g., 10.9.71.101
diff --git a/frc971/raspi/rootfs/build_kernel.sh b/frc971/raspi/rootfs/build_kernel.sh
new file mode 100755
index 0000000..cd97902
--- /dev/null
+++ b/frc971/raspi/rootfs/build_kernel.sh
@@ -0,0 +1,48 @@
+#!/bin/bash
+# This script builds the kernel for the raspberry pi.
+#
+# git@github.com:frc971/linux.git
+#
+# We are using the frc971-5.10-pi4-rt branch
+#
+# Point it at the version of that repo you want to build, and it'll generate a
+# .tar.gz of the bits to install.
+
+
+set -ex
+
+echo $#
+if [[ $# -lt 2 ]];
+then
+  echo "Pass in the kernel directory and then the destination .tar.gz"
+  exit 1
+fi
+
+export OUTPUT="$(realpath $(dirname $2))/$(basename ${2})"
+export TMPDIR="${OUTPUT}_tmpdir"
+
+mkdir -p "${TMPDIR}"
+mkdir -p "${TMPDIR}/fat32/overlays"
+mkdir -p "${TMPDIR}/ext4"
+
+pushd "${1}"
+
+export KERNEL=kernel8
+
+make ARCH=arm64 CROSS_COMPILE=aarch64-linux-gnu- Image modules dtbs -j 60
+
+cp arch/arm64/boot/Image "${TMPDIR}/fat32/$KERNEL.img"
+cp arch/arm64/boot/dts/broadcom/*.dtb "${TMPDIR}/fat32/"
+cp arch/arm64/boot/dts/overlays/*.dtb* "${TMPDIR}/fat32/overlays/"
+cp arch/arm64/boot/dts/overlays/README "${TMPDIR}/fat32/overlays/"
+
+make ARCH=arm64 CROSS_COMPILE=aarch64-linux-gnu- INSTALL_MOD_PATH="${TMPDIR}/ext4" modules_install
+
+cd "${TMPDIR}"
+tar cvzf "${OUTPUT}" --owner=0 --group=0 "./"
+
+popd
+
+rm -rf "${TMPDIR}"
+
+echo "Kernel is now available at: ${OUTPUT}"
diff --git a/frc971/raspi/rootfs/frc971chrt.service b/frc971/raspi/rootfs/frc971chrt.service
new file mode 100644
index 0000000..cc68934
--- /dev/null
+++ b/frc971/raspi/rootfs/frc971chrt.service
@@ -0,0 +1,9 @@
+[Unit]
+Description=Configure IRQs
+
+[Service]
+Type=oneshot
+ExecStart=/home/pi/robot_code/chrt.sh
+
+[Install]
+WantedBy=multi-user.target
diff --git a/frc971/raspi/rootfs/make_sd.sh b/frc971/raspi/rootfs/make_sd.sh
index 81f7727..3bafacc 100755
--- a/frc971/raspi/rootfs/make_sd.sh
+++ b/frc971/raspi/rootfs/make_sd.sh
@@ -4,7 +4,7 @@
 
 # Disk image to use for creating SD card
 # NOTE: You MUST run modify_rootfs.sh on this image BEFORE running make_sd.sh
-ORIG_IMAGE="2021-10-30-raspios-bullseye-armhf-lite.img"
+ORIG_IMAGE="2022-01-28-raspios-bullseye-arm64-lite.img"
 IMAGE=`echo ${ORIG_IMAGE} | sed s/.img/-frc-mods.img/`
 DEVICE="/dev/sda"
 
@@ -22,7 +22,7 @@
 sudo mount "${DEVICE}2" "${PARTITION}"
 
 function target() {
-  HOME=/root/ USER=root sudo proot -0 -q qemu-arm-static -w / -r "${PARTITION}" "$@"
+  HOME=/root/ USER=root sudo proot -0 -q qemu-aarch64-static -w / -r "${PARTITION}" "$@"
 }
 
 if [ "${1}" == "" ]; then
@@ -32,15 +32,15 @@
   target /root/bin/change_hostname.sh "${1}"
 fi
 
-echo "Starting a shell for any manual configuration"
-target /bin/bash --rcfile /root/.bashrc
-
 # Put a timestamp on when this card got created and by whom
 TIMESTAMP_FILE="${PARTITION}/home/pi/.DiskFlashedDate.txt"
 date > "${TIMESTAMP_FILE}"
 git rev-parse HEAD >> "${TIMESTAMP_FILE}"
 whoami >> "${TIMESTAMP_FILE}"
 
+echo "Starting a shell for any manual configuration"
+target /bin/bash --rcfile /root/.bashrc
+
 # Found I had to do a lazy force unmount ("-l" flag) to make it work reliably
 sudo umount -l "${PARTITION}"
 rmdir "${PARTITION}"
diff --git a/frc971/raspi/rootfs/modify_rootfs.sh b/frc971/raspi/rootfs/modify_rootfs.sh
index a340c64..0020f35 100755
--- a/frc971/raspi/rootfs/modify_rootfs.sh
+++ b/frc971/raspi/rootfs/modify_rootfs.sh
@@ -3,16 +3,18 @@
 set -xe
 
 # Full path to Raspberry Pi Bullseye disk image
-IMAGE="2021-10-30-raspios-bullseye-armhf-lite.img"
+IMAGE="2022-01-28-raspios-bullseye-arm64-lite.img"
+# Kernel built with build_kernel.sh
+KERNEL="kernel_5.10.tar.gz"
 BOOT_PARTITION="${IMAGE}.boot_partition"
 PARTITION="${IMAGE}.partition"
 
 function target() {
-  HOME=/root/ USER=root sudo proot -0 -q qemu-arm-static -w / -r "${PARTITION}" "$@"
+  HOME=/root/ USER=root sudo proot -0 -q qemu-aarch64-static -w / -r "${PARTITION}" "$@"
 }
 
 function user_pi_target() {
-  USER=root sudo proot -0 -q qemu-arm-static -w / -r "${PARTITION}" sudo -h 127.0.0.1 -u pi "$@"
+  USER=root sudo proot -0 -q qemu-aarch64-static -w / -r "${PARTITION}" sudo -h 127.0.0.1 -u pi "$@"
 }
 
 
@@ -37,6 +39,8 @@
 # For now, disable the new libcamera driver in favor of legacy ones
 sudo sed -i s/^camera_auto_detect=1/#camera_auto_detect=1/ "${BOOT_PARTITION}/config.txt"
 
+sudo tar -zxvf "${KERNEL}" --strip-components 2 -C ${BOOT_PARTITION}/ ./fat32
+
 # Seeing a race condition with umount, so doing lazy umount
 sudo umount -l "${BOOT_PARTITION}"
 rmdir "${BOOT_PARTITION}"
@@ -82,6 +86,7 @@
 sudo cp logind.conf "${PARTITION}/etc/systemd/logind.conf"
 sudo cp change_hostname.sh "${PARTITION}/tmp/change_hostname.sh"
 sudo cp frc971.service "${PARTITION}/etc/systemd/system/frc971.service"
+sudo cp frc971chrt.service "${PARTITION}/etc/systemd/system/frc971chrt.service"
 sudo cp rt.conf "${PARTITION}/etc/security/limits.d/rt.conf"
 sudo cp usb-mount@.service "${PARTITION}/etc/systemd/system/usb-mount@.service"
 sudo cp 99-usb-mount.rules "${PARTITION}/etc/udev/rules.d/99-usb-mount.rules"
@@ -89,6 +94,9 @@
 target /bin/mkdir -p /home/pi/.ssh/
 cat ~/.ssh/id_rsa.pub | target tee /home/pi/.ssh/authorized_keys
 
+sudo rm -rf "${PARTITION}/lib/modules/"*
+sudo tar -zxvf "${KERNEL}" --strip-components 4 -C "${PARTITION}/lib/modules/" ./ext4/lib/modules/
+
 # Downloads and installs our target libraries
 target /bin/bash /tmp/target_configure.sh
 
diff --git a/frc971/raspi/rootfs/target_configure.sh b/frc971/raspi/rootfs/target_configure.sh
index 3fd4d40..db3fb36 100755
--- a/frc971/raspi/rootfs/target_configure.sh
+++ b/frc971/raspi/rootfs/target_configure.sh
@@ -17,7 +17,6 @@
 
 apt-get install -y vim-nox \
   git \
-  python3-pip \
   cpufrequtils \
   libopencv-calib3d4.5 \
   libopencv-contrib4.5 \
@@ -37,7 +36,6 @@
   libopencv-videoio4.5 \
   libopencv-videostab4.5 \
   libopencv-viz4.5 \
-  python3-opencv \
   libnice10 \
   pmount \
   libnice-dev \
@@ -73,6 +71,7 @@
 
 systemctl enable ssh.service
 systemctl enable frc971.service
+systemctl enable frc971chrt.service
 
 # Default us to pi-971-1
 /root/bin/change_hostname.sh pi-971-1
diff --git a/frc971/vision/v4l2_reader.cc b/frc971/vision/v4l2_reader.cc
index 793d8cd..850fc7f 100644
--- a/frc971/vision/v4l2_reader.cc
+++ b/frc971/vision/v4l2_reader.cc
@@ -15,7 +15,7 @@
 V4L2Reader::V4L2Reader(aos::EventLoop *event_loop,
                        const std::string &device_name)
     : fd_(open(device_name.c_str(), O_RDWR | O_NONBLOCK)) {
-  PCHECK(fd_.get() != -1);
+  PCHECK(fd_.get() != -1) << " Failed to open device " << device_name;
 
   // First, clean up after anybody else who left the device streaming.
   StreamOff();
diff --git a/frc971/wpilib/imu.fbs b/frc971/wpilib/imu.fbs
index abd01e2..565e3a4 100644
--- a/frc971/wpilib/imu.fbs
+++ b/frc971/wpilib/imu.fbs
@@ -45,6 +45,11 @@
   // Operation section for more details on conditions that may cause this bit to
   // be set to 1.
   data_path_overrun:bool (id: 6);
+
+  // True indicates that the Raspberry Pi Pico recieved a packet
+  // from the imu that had a bad checksum but still sent a message
+  // containing a timestamp and encoder values.
+  checksum_mismatch:bool (id:7);
 }
 
 // Values returned from an IMU.
@@ -87,6 +92,24 @@
   // converted from fpga_timestamp.
   monotonic_timestamp_ns:long (id: 12);
 
+  // The timestamp when the values were captured by the Raspberry Pi Pico.
+  // This has microsecond precision.
+  pico_timestamp_us:int (id:20);
+
+  // The number of this reading produced from a 16-bit counter.
+  data_counter:int (id:19);
+
+  // The number of messages recieved by the Raspberry Pi that had bad checksums
+  failed_checksums:int (id:21);
+  // True if this packet has a bad checksum
+  // from the Raspberry Pi Pico to the Raspberry Pi.
+  checksum_failed:bool (id:22);
+
+  // The position of the left drivetrain encoder in meters
+  left_encoder:double (id: 17);
+  // The position of the right drivetrain encoder in meters
+  right_encoder:double (id: 18);
+
   // For an ADIS16470, the DIAG_STAT value immediately after reset.
   start_diag_stat:ADIS16470DiagStat (id: 13);
   // For an ADIS16470, the DIAG_STAT value after the initial sensor self test we
diff --git a/motors/RspBuckBoostv3/gafrc b/motors/RspBuckBoostv3/gafrc
new file mode 100644
index 0000000..c1bfff0
--- /dev/null
+++ b/motors/RspBuckBoostv3/gafrc
@@ -0,0 +1,2 @@
+(component-library "../symbols" "Custom Symbols")
+(source-library "..")
diff --git a/package.json b/package.json
index f60c6d4..7e6885b 100644
--- a/package.json
+++ b/package.json
@@ -2,6 +2,16 @@
   "name": "971-Robot-Code",
   "license": "MIT",
   "devDependencies": {
+    "@types/jasmine": "latest",
+    "@types/node": "latest",
+    "jasmine": "latest",
+    "karma-requirejs": "latest",
+    "karma-sourcemap-loader": "latest",
+    "karma-chrome-launcher": "latest",
+    "karma-firefox-launcher": "latest",
+    "karma": "latest",
+    "karma-jasmine": "latest",
+    "requirejs": "latest",
     "@bazel/concatjs": "latest",
     "@angular/animations": "latest",
     "@angular/core": "latest",
diff --git a/platform_mappings b/platform_mappings
deleted file mode 100644
index 1816850..0000000
--- a/platform_mappings
+++ /dev/null
@@ -1,38 +0,0 @@
-# https://docs.bazel.build/versions/master/platforms-intro.html#platform-mappings
-platforms:
-  //tools/platforms:linux_x86
-    --cpu=k8
-
-  //tools/platforms:linux_roborio
-    --cpu=roborio
-
-  //tools/platforms:linux_armv7
-    --cpu=armv7
-
-  //tools/platforms:cortex_m4f
-    --cpu=cortex-m4f
-
-  //tools/platforms:rp2040
-    --cpu=rp2040
-
-  //tools/platforms:linux_arm64
-    --cpu=arm64
-
-flags:
-  --cpu=k8
-    //tools/platforms:linux_x86
-
-  --cpu=roborio
-    //tools/platforms:linux_roborio
-
-  --cpu=armv7
-    //tools/platforms:linux_armv7
-
-  --cpu=cortex-m4f
-    //tools/platforms:cortex_m4f
-
-  --cpu=rp2040
-    //tools/platforms:rp2040
-
-  --cpu=arm64
-    //tools/platforms:linux_arm64
diff --git a/scouting/www/BUILD b/scouting/www/BUILD
index 88cadab..c22ea38 100644
--- a/scouting/www/BUILD
+++ b/scouting/www/BUILD
@@ -1,21 +1,23 @@
-load("@npm//@bazel/typescript:index.bzl", "ts_project")
+load("@npm//@bazel/typescript:index.bzl", "ts_library")
 load("//tools/build_rules:js.bzl", "rollup_bundle")
 load("@npm//@bazel/concatjs:index.bzl", "concatjs_devserver")
 load("@npm//@babel/cli:index.bzl", "babel")
 
-ts_project(
+ts_library(
     name = "app",
     srcs = glob([
         "*.ts",
+    ]),
+    angular_assets = glob([
         "*.ng.html",
     ]),
-    tsc = "@npm//@angular/compiler-cli/bin:ngc",
-    tsconfig = "//:tsconfig.json",
+    compiler = "//tools:tsc_wrapped_with_angular",
+    target_compatible_with = ["@platforms//cpu:x86_64"],
+    use_angular_plugin = True,
     visibility = ["//visibility:public"],
     deps = [
         "@npm//@angular/animations",
         "@npm//@angular/common",
-        "@npm//@angular/compiler",
         "@npm//@angular/core",
         "@npm//@angular/platform-browser",
     ],
diff --git a/third_party/abseil/absl/copts/configure_copts.bzl b/third_party/abseil/absl/copts/configure_copts.bzl
index 4d34254..46dc156 100644
--- a/third_party/abseil/absl/copts/configure_copts.bzl
+++ b/third_party/abseil/absl/copts/configure_copts.bzl
@@ -63,7 +63,7 @@
     # These configs have consistent flags to enable HWAES intsructions.
     cpu_configs = [
         "ppc",
-        "k8",
+        #"k8",
         "darwin_x86_64",
         "darwin",
         "x64_windows_msvc",
@@ -74,3 +74,7 @@
             name = "cpu_%s" % cpu,
             values = {"cpu": cpu},
         )
+    native.config_setting(
+        name = "cpu_k8",
+        constraint_values = ["@platforms//cpu:x86_64"],
+    )
diff --git a/third_party/bazel-toolchain/bazel_tools_changes/tools/cpp/unix_cc_toolchain_config.bzl b/third_party/bazel-toolchain/bazel_tools_changes/tools/cpp/unix_cc_toolchain_config.bzl
index 8de828f..0044dce 100755
--- a/third_party/bazel-toolchain/bazel_tools_changes/tools/cpp/unix_cc_toolchain_config.bzl
+++ b/third_party/bazel-toolchain/bazel_tools_changes/tools/cpp/unix_cc_toolchain_config.bzl
@@ -160,6 +160,17 @@
 
     action_configs.append(llvm_cov_action)
 
+    objcopy_embed_data_action = action_config(
+        action_name = "objcopy_embed_data",
+        tools = [
+            tool(
+                path = ctx.attr.tool_paths["objcopy"],
+            ),
+        ],
+    )
+
+    action_configs.append(objcopy_embed_data_action)
+
     supports_pic_feature = feature(
         name = "supports_pic",
         enabled = True,
diff --git a/third_party/flatbuffers/build_defs.bzl b/third_party/flatbuffers/build_defs.bzl
index 5add25f..c547a7d 100644
--- a/third_party/flatbuffers/build_defs.bzl
+++ b/third_party/flatbuffers/build_defs.bzl
@@ -6,6 +6,7 @@
 """
 
 load("@npm//@bazel/typescript:index.bzl", "ts_library")
+load("@io_bazel_rules_go//go:def.bzl", "go_library")
 
 flatc_path = "@com_github_google_flatbuffers//:flatc"
 
@@ -31,6 +32,10 @@
     "--gen-name-strings",
 ]
 
+DEFAULT_FLATC_GO_ARGS = [
+    "--gen-onefile",
+]
+
 DEFAULT_FLATC_TS_ARGS = [
     "--gen-all",
     "--no-fb-import",
@@ -339,6 +344,42 @@
         deps = ["@com_github_google_flatbuffers//:flatpy"],
     )
 
+def flatbuffer_go_library(
+        name,
+        srcs,
+        importpath,
+        compatible_with = None,
+        target_compatible_with = None,
+        includes = [],
+        include_paths = DEFAULT_INCLUDE_PATHS,
+        flatc_args = DEFAULT_FLATC_GO_ARGS,
+        visibility = None,
+        srcs_filegroup_visibility = None):
+    srcs_lib = "%s_srcs" % (name)
+    outs = ["%s_generated.go" % (s.replace(".fbs", "").split("/")[-1]) for s in srcs]
+    flatc_args = flatc_args + ["--go-namespace", importpath.split("/")[-1]]
+
+    flatbuffer_library_public(
+        name = srcs_lib,
+        srcs = srcs,
+        outs = outs,
+        language_flag = "--go",
+        includes = includes,
+        include_paths = include_paths,
+        flatc_args = flatc_args,
+        compatible_with = compatible_with,
+        target_compatible_with = target_compatible_with,
+    )
+    go_library(
+        name = name,
+        srcs = outs,
+        deps = ["@com_github_google_flatbuffers//go"],
+        importpath = importpath,
+        visibility = visibility,
+        compatible_with = compatible_with,
+        target_compatible_with = target_compatible_with,
+    )
+
 def flatbuffer_ts_library(
         name,
         srcs,
diff --git a/third_party/pico-sdk/hex.bzl b/third_party/pico-sdk/hex.bzl
index 5e9dfae..31c951c 100644
--- a/third_party/pico-sdk/hex.bzl
+++ b/third_party/pico-sdk/hex.bzl
@@ -7,7 +7,7 @@
         executable = True,
         output_to_bindir = True,
         target_compatible_with = target_compatible_with,
-        toolchains = ["@bazel_tools//tools/cpp:current_cc_toolchain"],
+        toolchains = ["//tools/cpp:cc_toolchain_make_variables"],
     )
 
 def uf2_from_elf(name, target_compatible_with = None):
diff --git a/third_party/rules_webtesting/rules_webtesting.patch b/third_party/rules_webtesting/rules_webtesting.patch
new file mode 100644
index 0000000..90b7716
--- /dev/null
+++ b/third_party/rules_webtesting/rules_webtesting.patch
@@ -0,0 +1,56 @@
+diff --git a/BUILD.bazel b/BUILD.bazel
+index ab52bbb..5f9f4c3 100644
+--- a/BUILD.bazel
++++ b/BUILD.bazel
+@@ -24,3 +24,17 @@ gazelle(
+     name = "gazelle",
+     prefix = "github.com/bazelbuild/rules_webtesting",
+ )
++
++genrule(
++    name = "generate_error_bin",
++    outs = ["error_bin.sh"],
++    cmd = "echo 'exit 1' > $(OUTS)",
++    executable = True,
++)
++
++sh_binary(
++    name = "error_bin",
++    srcs = ["error_bin.sh"],
++    visibility = ["//visibility:public"],
++    target_compatible_with = ["@platforms//:incompatible"],
++)
+diff --git a/third_party/chromedriver/BUILD.bazel b/third_party/chromedriver/BUILD.bazel
+index 3d794d4..3644474 100644
+--- a/third_party/chromedriver/BUILD.bazel
++++ b/third_party/chromedriver/BUILD.bazel
+@@ -30,6 +30,7 @@ alias(
+         "//common/conditions:macos_x64": "@org_chromium_chromedriver_macos_x64//:metadata",
+         "//common/conditions:macos_arm64": "@org_chromium_chromedriver_macos_arm64//:metadata",
+         "//common/conditions:windows_x64": "@org_chromium_chromedriver_windows_x64//:metadata",
++        "//conditions:default": "//:error_bin",
+     }),
+     visibility = ["//browsers:__subpackages__"],
+ )
+diff --git a/third_party/chromium/BUILD.bazel b/third_party/chromium/BUILD.bazel
+index 6d8c6e0..7702fb9 100644
+--- a/third_party/chromium/BUILD.bazel
++++ b/third_party/chromium/BUILD.bazel
+@@ -26,6 +26,7 @@ alias(
+         "//common/conditions:macos_x64": "@org_chromium_chromium_macos_x64//:metadata",
+         "//common/conditions:macos_arm64": "@org_chromium_chromium_macos_arm64//:metadata",
+         "//common/conditions:windows_x64": "@org_chromium_chromium_windows_x64//:metadata",
++        "//conditions:default": "//:error_bin",
+     }),
+     visibility = ["//browsers:__subpackages__"],
+ )
+diff --git a/web/internal/executable_name.bzl b/web/internal/executable_name.bzl
+index b103868..12df0cc 100644
+--- a/web/internal/executable_name.bzl
++++ b/web/internal/executable_name.bzl
+@@ -26,4 +26,5 @@ def get_platform_executable_name():
+         "//common/conditions:macos_x64": "main_darwin_x64",
+         "//common/conditions:macos_arm64": "main_darwin_arm64",
+         "//common/conditions:windows_x64": "main_windows_x64.exe",
++        "//conditions:default": "//:error_bin",
+     })
diff --git a/tools/BUILD b/tools/BUILD
index a7d165d..d64d602 100644
--- a/tools/BUILD
+++ b/tools/BUILD
@@ -1,3 +1,5 @@
+load("@build_bazel_rules_nodejs//:index.bzl", "nodejs_binary")
+
 package(default_visibility = ["//visibility:public"])
 
 exports_files(["test_sharding_compliant"])
@@ -72,3 +74,13 @@
     name = "has_ubsan",
     values = {"define": "have_ubsan=true"},
 )
+
+nodejs_binary(
+    name = "tsc_wrapped_with_angular",
+    data = [
+        "@npm//@angular/compiler-cli",
+        "@npm//@bazel/typescript",
+    ],
+    entry_point = "@npm//:node_modules/@bazel/typescript/internal/tsc_wrapped/tsc_wrapped.js",
+    target_compatible_with = ["@platforms//cpu:x86_64"],
+)
diff --git a/tools/bazel b/tools/bazel
index e72b44e..edb1aca 100755
--- a/tools/bazel
+++ b/tools/bazel
@@ -24,7 +24,7 @@
   exec "${BAZEL_OVERRIDE}" "$@"
 fi
 
-readonly VERSION="4.2.2"
+readonly VERSION="5.0.0"
 
 readonly DOWNLOAD_DIR="${HOME}/.cache/bazel"
 # Directory to unpack bazel into.  This must change whenever bazel changes.
@@ -103,6 +103,7 @@
 ENVIRONMENT_VARIABLES+=(HOME="${HOME}")
 ENVIRONMENT_VARIABLES+=(TERM="${TERM}")
 ENVIRONMENT_VARIABLES+=(LANG="${LANG:-C}")
+ENVIRONMENT_VARIABLES+=(BAZEL_DO_NOT_DETECT_CPP_TOOLCHAIN=1)
 
 if [[ ! -z "${DISPLAY+x}" ]]; then
   ENVIRONMENT_VARIABLES+=(DISPLAY="${DISPLAY}")
diff --git a/tools/ci/buildkite.yaml b/tools/ci/buildkite.yaml
index c4af4a4..e20c523 100644
--- a/tools/ci/buildkite.yaml
+++ b/tools/ci/buildkite.yaml
@@ -1,5 +1,5 @@
 env:
-  STARTUP: --max_idle_secs=0 --watchfs
+  STARTUP: --max_idle_secs=0
   COMMON: -c opt --stamp=no --curses=yes --symlink_prefix=/ --disk_cache=~/.cache/bazel/disk_cache/ --repo_env=FRC971_RUNNING_IN_CI=1
   TARGETS: //... @com_github_google_glog//... @com_google_ceres_solver//... @com_github_rawrtc_rawrtc//... @com_google_googletest//...
   M4F_TARGETS: //...
diff --git a/tools/cpp/BUILD b/tools/cpp/BUILD
index db5fa06..5c36559 100644
--- a/tools/cpp/BUILD
+++ b/tools/cpp/BUILD
@@ -1,19 +1,11 @@
 load(":toolchain_config.bzl", "cc_toolchain_config")
+load(":toolchain_make_variables.bzl", "cc_toolchain_make_variables")
 
 package(default_visibility = ["//visibility:public"])
 
-cc_toolchain_suite(
-    name = "toolchain",
-    toolchains = {
-        "k8": "@llvm_toolchain//:cc-clang-x86_64-linux",
-        "armv7": "@llvm_toolchain//:cc-clang-armv7-linux",
-        "arm64": "@llvm_toolchain//:cc-clang-aarch64-linux",
-        "roborio": ":cc-compiler-roborio",
-        "cortex-m4f": ":cc-compiler-cortex-m4f",
-        "rp2040": ":cc-compiler-rp2040",
-    },
-    visibility = ["//visibility:public"],
-)
+# Use this instead of @bazel_tools//tools/cpp:current_cc_toolchain.
+# This one supports platforms.
+cc_toolchain_make_variables(name = "cc_toolchain_make_variables")
 
 [
     cc_toolchain_config(
diff --git a/tools/cpp/toolchain_make_variables.bzl b/tools/cpp/toolchain_make_variables.bzl
new file mode 100644
index 0000000..7c06e1d
--- /dev/null
+++ b/tools/cpp/toolchain_make_variables.bzl
@@ -0,0 +1,39 @@
+load("@bazel_tools//tools/cpp:toolchain_utils.bzl", "find_cpp_toolchain")
+
+def _cc_toolchain_make_variables_impl(ctx):
+    """Supports make variables for toolchains in a platforms setup.
+
+    The upstream @bazel_tools//tools/cpp:current_cc_toolchain target on its own
+    doesn't appear to work with platforms. It only works when using --cpu.
+    """
+    toolchain = find_cpp_toolchain(ctx)
+
+    feature_configuration = cc_common.configure_features(
+        ctx = ctx,
+        cc_toolchain = toolchain,
+        requested_features = ctx.features,
+        unsupported_features = ctx.disabled_features,
+    )
+    objcopy = cc_common.get_tool_for_action(
+        feature_configuration = feature_configuration,
+        action_name = "objcopy_embed_data",
+    )
+
+    return [
+        platform_common.TemplateVariableInfo({
+            "OBJCOPY": objcopy,
+        }),
+        DefaultInfo(files = toolchain.all_files),
+    ]
+
+cc_toolchain_make_variables = rule(
+    implementation = _cc_toolchain_make_variables_impl,
+    attrs = {
+        # This is a dependency of find_cpp_toolchain().
+        "_toolchain": attr.label(
+            default = Label("@bazel_tools//tools/cpp:current_cc_toolchain"),
+        ),
+    },
+    fragments = ["cpp"],
+    toolchains = ["@bazel_tools//tools/cpp:toolchain_type"],
+)
diff --git a/tools/dependency_rewrite b/tools/dependency_rewrite
index cc1de8c..f2172cc 100644
--- a/tools/dependency_rewrite
+++ b/tools/dependency_rewrite
@@ -6,6 +6,7 @@
 rewrite mirror.bazel.build/(.*) software.frc971.org/Build-Dependencies/mirror.bazel.build/$1
 rewrite nodejs.org/(.*) software.frc971.org/Build-Dependencies/nodejs.org/$1
 rewrite static.rust-lang.org/(.*) software.frc971.org/Build-Dependencies/static.rust-lang.org/$1
+rewrite storage.googleapis.com/(.*) software.frc971.org/Build-Dependencies/storage.googleapis.com/$1
 allow golang.org
 
 allow software.frc971.org
diff --git a/tools/platforms/BUILD b/tools/platforms/BUILD
index 4127883..37fed2e 100644
--- a/tools/platforms/BUILD
+++ b/tools/platforms/BUILD
@@ -7,6 +7,7 @@
         "@platforms//cpu:x86_64",
         "//tools/platforms/go:has_support",
         "//tools/platforms/rust:has_support",
+        "//tools/platforms/nodejs:has_support",
     ],
 )
 
@@ -18,6 +19,7 @@
         "//tools/platforms/hardware:raspberry_pi",
         "//tools/platforms/go:lacks_support",
         "//tools/platforms/rust:has_support",
+        "//tools/platforms/nodejs:lacks_support",
     ],
 )
 
@@ -29,6 +31,7 @@
         "//tools/platforms/hardware:raspberry_pi",
         "//tools/platforms/go:lacks_support",
         "//tools/platforms/rust:has_support",
+        "//tools/platforms/nodejs:lacks_support",
     ],
 )
 
@@ -40,6 +43,7 @@
         "//tools/platforms/hardware:roborio",
         "//tools/platforms/go:lacks_support",
         "//tools/platforms/rust:has_support",
+        "//tools/platforms/nodejs:lacks_support",
     ],
 )
 
@@ -50,6 +54,7 @@
         "//tools/platforms/hardware:cortex_m4f",
         "//tools/platforms/go:lacks_support",
         "//tools/platforms/rust:lacks_support",
+        "//tools/platforms/nodejs:lacks_support",
     ],
 )
 
@@ -60,6 +65,7 @@
         "//tools/platforms/hardware:cortex_m0plus",
         "//tools/platforms/go:lacks_support",
         "//tools/platforms/rust:lacks_support",
+        "//tools/platforms/nodejs:lacks_support",
     ],
 )
 
diff --git a/tools/platforms/nodejs/BUILD b/tools/platforms/nodejs/BUILD
new file mode 100644
index 0000000..3040964
--- /dev/null
+++ b/tools/platforms/nodejs/BUILD
@@ -0,0 +1,13 @@
+package(default_visibility = ["//visibility:public"])
+
+constraint_setting(name = "node_support")
+
+constraint_value(
+    name = "has_support",
+    constraint_setting = ":node_support",
+)
+
+constraint_value(
+    name = "lacks_support",
+    constraint_setting = ":node_support",
+)
diff --git a/tools/ts/BUILD b/tools/ts/BUILD
new file mode 100644
index 0000000..697e376
--- /dev/null
+++ b/tools/ts/BUILD
@@ -0,0 +1,32 @@
+load("@bazel_skylib//rules:write_file.bzl", "write_file")
+load("@build_bazel_rules_nodejs//toolchains/node:node_toolchain.bzl", "node_toolchain")
+
+write_file(
+    name = "noop_error_exit",
+    out = "noop_error_exit.sh",
+    content = [
+        "#!/bin/bash",
+        "echo 'This should never be executed. Something went wrong.' >&2",
+        "echo 'This NOOP NodeJs toolchain should never be executed. Something went wrong.' >&2",
+        "echo 'Check that your target has `target_compatible_with` set to a platform that supports NodeJs.' >&2",
+        "exit 1",
+    ],
+    is_executable = True,
+)
+
+node_toolchain(
+    name = "noop_node_toolchain_impl",
+    target_tool = ":noop_error_exit",
+)
+
+toolchain(
+    name = "noop_node_toolchain",
+    exec_compatible_with = [
+        "@platforms//os:linux",
+    ],
+    target_compatible_with = [
+        "//tools/platforms/nodejs:lacks_support",
+    ],
+    toolchain = ":noop_node_toolchain_impl",
+    toolchain_type = "@build_bazel_rules_nodejs//toolchains/node:toolchain_type",
+)
diff --git a/y2020/vision/calibration.cc b/y2020/vision/calibration.cc
index 0b05d10..9293d50 100644
--- a/y2020/vision/calibration.cc
+++ b/y2020/vision/calibration.cc
@@ -2,6 +2,7 @@
 #include <opencv2/calib3d.hpp>
 #include <opencv2/highgui/highgui.hpp>
 #include <opencv2/imgproc.hpp>
+#include <regex>
 
 #include "Eigen/Dense"
 #include "Eigen/Geometry"
@@ -13,23 +14,26 @@
 #include "aos/util/file.h"
 #include "y2020/vision/charuco_lib.h"
 
-DEFINE_string(config, "config.json", "Path to the config file to use.");
-DEFINE_string(pi, "pi-7971-1", "Pi name to calibrate.");
 DEFINE_string(calibration_folder, ".", "Folder to place calibration files.");
+DEFINE_string(camera_id, "", "Camera ID in format YY-NN-- year and number.");
+DEFINE_string(config, "config.json", "Path to the config file to use.");
 DEFINE_bool(display_undistorted, false,
             "If true, display the undistorted image.");
+DEFINE_string(pi, "", "Pi name to calibrate.");
 
 namespace frc971 {
 namespace vision {
 
 class Calibration {
  public:
-  Calibration(aos::ShmEventLoop *event_loop, std::string_view pi)
+  Calibration(aos::ShmEventLoop *event_loop, std::string_view pi,
+              std::string_view camera_id)
       : event_loop_(event_loop),
         pi_(pi),
         pi_number_(aos::network::ParsePiNumber(pi)),
-        prev_rvec_(Eigen::Vector3d::Zero()),
-        prev_tvec_(Eigen::Vector3d::Zero()),
+        camera_id_(camera_id),
+        H_camera_board_(Eigen::Affine3d()),
+        prev_H_camera_board_(Eigen::Affine3d()),
         charuco_extractor_(
             event_loop, pi,
             [this](cv::Mat rgb_image,
@@ -37,11 +41,15 @@
                    std::vector<int> charuco_ids,
                    std::vector<cv::Point2f> charuco_corners, bool valid,
                    Eigen::Vector3d rvec_eigen, Eigen::Vector3d tvec_eigen) {
-              HandleCharuco(rgb_image, eof, charuco_ids, charuco_corners,
-                            valid, rvec_eigen, tvec_eigen);
+              HandleCharuco(rgb_image, eof, charuco_ids, charuco_corners, valid,
+                            rvec_eigen, tvec_eigen);
             }) {
     CHECK(pi_number_) << ": Invalid pi number " << pi
                       << ", failed to parse pi number";
+    std::regex re{"^[0-9][0-9]-[0-9][0-9]"};
+    CHECK(std::regex_match(camera_id_, re))
+        << ": Invalid camera_id '" << camera_id_
+        << "', should be of form YY-NN";
   }
 
   void HandleCharuco(cv::Mat rgb_image,
@@ -67,16 +75,15 @@
     // Calibration calculates rotation and translation delta from last image
     // captured to automatically capture next image
 
-    Eigen::Matrix3d r_aff =
-        Eigen::AngleAxisd(rvec_eigen.norm(), rvec_eigen / rvec_eigen.norm())
-            .toRotationMatrix();
-    Eigen::Matrix3d prev_r_aff =
-        Eigen::AngleAxisd(prev_rvec_.norm(), prev_rvec_ / prev_rvec_.norm())
-            .toRotationMatrix();
+    Eigen::Affine3d H_board_camera =
+        Eigen::Translation3d(tvec_eigen) *
+        Eigen::AngleAxisd(rvec_eigen.norm(), rvec_eigen / rvec_eigen.norm());
+    H_camera_board_ = H_board_camera.inverse();
+    Eigen::Affine3d H_delta = H_board_camera * prev_H_camera_board_;
 
-    Eigen::AngleAxisd delta_r = Eigen::AngleAxisd(r_aff * prev_r_aff.inverse());
+    Eigen::AngleAxisd delta_r = Eigen::AngleAxisd(H_delta.rotation());
 
-    Eigen::Vector3d delta_t = tvec_eigen - prev_tvec_;
+    Eigen::Vector3d delta_t = H_delta.translation();
 
     double r_norm = std::abs(delta_r.angle());
     double t_norm = delta_t.norm();
@@ -84,8 +91,7 @@
     int keystroke = cv::waitKey(1);
     if (r_norm > kDeltaRThreshold || t_norm > kDeltaTThreshold) {
       if (valid) {
-        prev_rvec_ = rvec_eigen;
-        prev_tvec_ = tvec_eigen;
+        prev_H_camera_board_ = H_camera_board_;
 
         all_charuco_ids_.emplace_back(std::move(charuco_ids));
         all_charuco_corners_.emplace_back(std::move(charuco_corners));
@@ -113,6 +119,8 @@
 
   void MaybeCalibrate() {
     if (all_charuco_ids_.size() >= 50) {
+      LOG(INFO) << "Beginning calibration on " << all_charuco_ids_.size()
+                << " images";
       cv::Mat cameraMatrix, distCoeffs;
       std::vector<cv::Mat> rvecs, tvecs;
       cv::Mat stdDeviationsIntrinsics, stdDeviationsExtrinsics, perViewErrors;
@@ -131,6 +139,8 @@
       flatbuffers::FlatBufferBuilder fbb;
       flatbuffers::Offset<flatbuffers::String> name_offset =
           fbb.CreateString(absl::StrFormat("pi%d", pi_number_.value()));
+      flatbuffers::Offset<flatbuffers::String> camera_id_offset =
+          fbb.CreateString(camera_id_);
       flatbuffers::Offset<flatbuffers::Vector<float>> intrinsics_offset =
           fbb.CreateVector<float>(9u, [&cameraMatrix](size_t i) {
             return static_cast<float>(
@@ -154,6 +164,7 @@
           aos::realtime_clock::now();
       camera_calibration_builder.add_node_name(name_offset);
       camera_calibration_builder.add_team_number(team_number.value());
+      camera_calibration_builder.add_camera_id(camera_id_offset);
       camera_calibration_builder.add_calibration_timestamp(
           realtime_now.time_since_epoch().count());
       camera_calibration_builder.add_intrinsics(intrinsics_offset);
@@ -168,8 +179,9 @@
 
       const std::string calibration_filename =
           FLAGS_calibration_folder +
-          absl::StrFormat("/calibration_pi-%d-%d_%s.json", team_number.value(),
-                          pi_number_.value(), time_ss.str());
+          absl::StrFormat("/calibration_pi-%d-%d_cam-%s_%s.json",
+                          team_number.value(), pi_number_.value(), camera_id_,
+                          time_ss.str());
 
       LOG(INFO) << calibration_filename << " -> "
                 << aos::FlatbufferToJson(camera_calibration,
@@ -190,12 +202,13 @@
   aos::ShmEventLoop *event_loop_;
   std::string pi_;
   const std::optional<uint16_t> pi_number_;
+  const std::string camera_id_;
 
   std::vector<std::vector<int>> all_charuco_ids_;
   std::vector<std::vector<cv::Point2f>> all_charuco_corners_;
 
-  Eigen::Vector3d prev_rvec_;
-  Eigen::Vector3d prev_tvec_;
+  Eigen::Affine3d H_camera_board_;
+  Eigen::Affine3d prev_H_camera_board_;
 
   CharucoExtractor charuco_extractor_;
 };
@@ -208,7 +221,12 @@
 
   aos::ShmEventLoop event_loop(&config.message());
 
-  Calibration extractor(&event_loop, FLAGS_pi);
+  std::string hostname = FLAGS_pi;
+  if (hostname == "") {
+    hostname = aos::network::GetHostname();
+    LOG(INFO) << "Using pi name from hostname as " << hostname;
+  }
+  Calibration extractor(&event_loop, hostname, FLAGS_camera_id);
 
   event_loop.Run();
 
diff --git a/y2020/vision/calibration_accumulator.cc b/y2020/vision/calibration_accumulator.cc
index e77c74b..9f550c5 100644
--- a/y2020/vision/calibration_accumulator.cc
+++ b/y2020/vision/calibration_accumulator.cc
@@ -22,10 +22,15 @@
 using aos::monotonic_clock;
 namespace chrono = std::chrono;
 
+constexpr double kG = 9.807;
+
 void CalibrationData::AddCameraPose(
     distributed_clock::time_point distributed_now, Eigen::Vector3d rvec,
     Eigen::Vector3d tvec) {
-  rot_trans_points_.emplace_back(distributed_now, std::make_pair(rvec, tvec));
+  // Always start with IMU reading...
+  if (!imu_points_.empty() && imu_points_[0].first < distributed_now) {
+    rot_trans_points_.emplace_back(distributed_now, std::make_pair(rvec, tvec));
+  }
 }
 
 void CalibrationData::AddImu(distributed_clock::time_point distributed_now,
@@ -167,7 +172,7 @@
 
   data_->AddImu(imu_factory_->ToDistributedClock(monotonic_clock::time_point(
                     chrono::nanoseconds(imu->monotonic_timestamp_ns()))),
-                gyro, accel);
+                gyro, accel * kG);
 }
 
 }  // namespace vision
diff --git a/y2020/vision/calibration_accumulator.h b/y2020/vision/calibration_accumulator.h
index 0f1bff7..7bff9f0 100644
--- a/y2020/vision/calibration_accumulator.h
+++ b/y2020/vision/calibration_accumulator.h
@@ -13,11 +13,17 @@
 namespace frc971 {
 namespace vision {
 
+// This class provides an interface for an application to be notified of all
+// camera and IMU samples in order with the correct timestamps.
 class CalibrationDataObserver {
  public:
+  // Observes a camera sample at the corresponding time t, and with the
+  // corresponding rotation and translation vectors rt.
   virtual void UpdateCamera(aos::distributed_clock::time_point t,
                             std::pair<Eigen::Vector3d, Eigen::Vector3d> rt) = 0;
 
+  // Observes an IMU sample at the corresponding time t, and with the
+  // corresponding angular velocity and linear acceleration vectors wa.
   virtual void UpdateIMU(aos::distributed_clock::time_point t,
                          std::pair<Eigen::Vector3d, Eigen::Vector3d> wa) = 0;
 };
diff --git a/y2020/vision/charuco_lib.cc b/y2020/vision/charuco_lib.cc
index 0df820b..8677cbb 100644
--- a/y2020/vision/charuco_lib.cc
+++ b/y2020/vision/charuco_lib.cc
@@ -137,7 +137,7 @@
     const double age_double =
         std::chrono::duration_cast<std::chrono::duration<double>>(age).count();
     if (age > std::chrono::milliseconds(100)) {
-      LOG(INFO) << "Age: " << age_double << ", getting behind, skipping";
+      VLOG(2) << "Age: " << age_double << ", getting behind, skipping";
       return;
     }
     // Create color image:
diff --git a/y2020/vision/extrinsics_calibration.cc b/y2020/vision/extrinsics_calibration.cc
index c7ef752..f2ac926 100644
--- a/y2020/vision/extrinsics_calibration.cc
+++ b/y2020/vision/extrinsics_calibration.cc
@@ -22,6 +22,7 @@
 
 DEFINE_string(config, "config.json", "Path to the config file to use.");
 DEFINE_string(pi, "pi-7971-2", "Pi name to calibrate.");
+DEFINE_bool(plot, false, "Whether to plot the resulting data.");
 
 namespace frc971 {
 namespace vision {
@@ -29,6 +30,8 @@
 using aos::distributed_clock;
 using aos::monotonic_clock;
 
+constexpr double kGravity = 9.8;
+
 // The basic ideas here are taken from Kalibr.
 // (https://github.com/ethz-asl/kalibr), but adapted to work with AOS, and to be
 // simpler.
@@ -61,48 +64,95 @@
 template <typename Scalar>
 class CeresPoseFilter : public CalibrationDataObserver {
  public:
+  typedef Eigen::Transform<Scalar, 3, Eigen::Affine> Affine3s;
+
   CeresPoseFilter(Eigen::Quaternion<Scalar> initial_orientation,
                   Eigen::Quaternion<Scalar> imu_to_camera,
-                  Eigen::Matrix<Scalar, 3, 1> imu_bias)
+                  Eigen::Matrix<Scalar, 3, 1> gyro_bias,
+                  Eigen::Matrix<Scalar, 6, 1> initial_state,
+                  Eigen::Quaternion<Scalar> board_to_world,
+                  Eigen::Matrix<Scalar, 3, 1> imu_to_camera_translation,
+                  Scalar gravity_scalar,
+                  Eigen::Matrix<Scalar, 3, 1> accelerometer_bias)
       : accel_(Eigen::Matrix<double, 3, 1>::Zero()),
         omega_(Eigen::Matrix<double, 3, 1>::Zero()),
-        imu_bias_(imu_bias),
+        imu_bias_(gyro_bias),
         orientation_(initial_orientation),
-        x_hat_(Eigen::Matrix<Scalar, 6, 1>::Zero()),
+        x_hat_(initial_state),
         p_(Eigen::Matrix<Scalar, 6, 6>::Zero()),
-        imu_to_camera_(imu_to_camera) {}
+        imu_to_camera_rotation_(imu_to_camera),
+        imu_to_camera_translation_(imu_to_camera_translation),
+        board_to_world_(board_to_world),
+        gravity_scalar_(gravity_scalar),
+        accelerometer_bias_(accelerometer_bias) {}
 
-  virtual void ObserveCameraUpdate(distributed_clock::time_point /*t*/,
-                                   Eigen::Vector3d /*board_to_camera_rotation*/,
-                                   Eigen::Quaternion<Scalar> /*imu_to_world*/) {
-  }
+  Scalar gravity_scalar() { return gravity_scalar_; }
 
+  virtual void ObserveCameraUpdate(
+      distributed_clock::time_point /*t*/,
+      Eigen::Vector3d /*board_to_camera_rotation*/,
+      Eigen::Quaternion<Scalar> /*imu_to_world_rotation*/,
+      Affine3s /*imu_to_world*/) {}
+
+  // Observes a camera measurement by applying a kalman filter correction and
+  // accumulating up the error associated with the step.
   void UpdateCamera(distributed_clock::time_point t,
                     std::pair<Eigen::Vector3d, Eigen::Vector3d> rt) override {
     Integrate(t);
 
-    Eigen::Quaternion<Scalar> board_to_camera(
+    const Eigen::Quaternion<Scalar> board_to_camera_rotation(
         frc971::controls::ToQuaternionFromRotationVector(rt.first)
             .cast<Scalar>());
+    const Affine3s board_to_camera =
+        Eigen::Translation3d(rt.second).cast<Scalar>() *
+        board_to_camera_rotation;
+
+    const Affine3s imu_to_camera =
+        imu_to_camera_translation_ * imu_to_camera_rotation_;
 
     // This converts us from (facing the board),
     //   x right, y up, z towards us -> x right, y away, z up.
     // Confirmed to be right.
-    Eigen::Quaternion<Scalar> board_to_world(
-        Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX()).cast<Scalar>());
 
     // Want world -> imu rotation.
     // world <- board <- camera <- imu.
-    const Eigen::Quaternion<Scalar> imu_to_world =
-        board_to_world * board_to_camera.inverse() * imu_to_camera_;
+    const Eigen::Quaternion<Scalar> imu_to_world_rotation =
+        board_to_world_ * board_to_camera_rotation.inverse() *
+        imu_to_camera_rotation_;
 
-    const Eigen::Quaternion<Scalar> error(imu_to_world.inverse() *
+    const Affine3s imu_to_world =
+        board_to_world_ * board_to_camera.inverse() * imu_to_camera;
+
+    const Eigen::Matrix<Scalar, 3, 1> z =
+        imu_to_world * Eigen::Matrix<Scalar, 3, 1>::Zero();
+
+    Eigen::Matrix<Scalar, 3, 6> H = Eigen::Matrix<Scalar, 3, 6>::Zero();
+    H(0, 0) = static_cast<Scalar>(1.0);
+    H(1, 1) = static_cast<Scalar>(1.0);
+    H(2, 2) = static_cast<Scalar>(1.0);
+    const Eigen::Matrix<Scalar, 3, 1> y = z - H * x_hat_;
+
+    const Eigen::Matrix<double, 3, 3> R =
+        (::Eigen::DiagonalMatrix<double, 3>().diagonal() << ::std::pow(0.01, 2),
+         ::std::pow(0.01, 2), ::std::pow(0.01, 2))
+            .finished()
+            .asDiagonal();
+
+    const Eigen::Matrix<Scalar, 3, 3> S =
+        H * p_ * H.transpose() + R.cast<Scalar>();
+    const Eigen::Matrix<Scalar, 6, 3> K = p_ * H.transpose() * S.inverse();
+
+    x_hat_ += K * y;
+    p_ = (Eigen::Matrix<Scalar, 6, 6>::Identity() - K * H) * p_;
+
+    const Eigen::Quaternion<Scalar> error(imu_to_world_rotation.inverse() *
                                           orientation());
 
     errors_.emplace_back(
         Eigen::Matrix<Scalar, 3, 1>(error.x(), error.y(), error.z()));
+    position_errors_.emplace_back(y);
 
-    ObserveCameraUpdate(t, rt.first, imu_to_world);
+    ObserveCameraUpdate(t, rt.first, imu_to_world_rotation, imu_to_world);
   }
 
   virtual void ObserveIMUUpdate(
@@ -120,14 +170,16 @@
 
   const Eigen::Quaternion<Scalar> &orientation() const { return orientation_; }
 
-  std::vector<Eigen::Matrix<Scalar, 3, 1>> errors_;
-
-  // Returns the angular errors for each camera sample.
   size_t num_errors() const { return errors_.size(); }
   Scalar errorx(size_t i) const { return errors_[i].x(); }
   Scalar errory(size_t i) const { return errors_[i].y(); }
   Scalar errorz(size_t i) const { return errors_[i].z(); }
 
+  size_t num_perrors() const { return position_errors_.size(); }
+  Scalar errorpx(size_t i) const { return position_errors_[i].x(); }
+  Scalar errorpy(size_t i) const { return position_errors_[i].y(); }
+  Scalar errorpz(size_t i) const { return position_errors_[i].z(); }
+
  private:
   Eigen::Matrix<Scalar, 46, 1> Pack(Eigen::Quaternion<Scalar> q,
                                     Eigen::Matrix<Scalar, 6, 1> x_hat,
@@ -151,7 +203,7 @@
     return std::make_tuple(q, x_hat, p);
   }
 
-  Eigen::Matrix<Scalar, 46, 1> Derivitive(
+  Eigen::Matrix<Scalar, 46, 1> Derivative(
       const Eigen::Matrix<Scalar, 46, 1> &input) {
     auto [q, x_hat, p] = UnPack(input);
 
@@ -160,25 +212,48 @@
     omega_q.vec() = 0.5 * (omega_.cast<Scalar>() - imu_bias_);
     Eigen::Matrix<Scalar, 4, 1> q_dot = (q * omega_q).coeffs();
 
-    Eigen::Matrix<Scalar, 6, 1> x_hat_dot = Eigen::Matrix<Scalar, 6, 1>::Zero();
-    x_hat_dot(0, 0) = x_hat(3, 0);
-    x_hat_dot(1, 0) = x_hat(4, 0);
-    x_hat_dot(2, 0) = x_hat(5, 0);
-    x_hat_dot.template block<3, 1>(3, 0) = accel_.cast<Scalar>();
+    Eigen::Matrix<double, 6, 6> A = Eigen::Matrix<double, 6, 6>::Zero();
+    A(0, 3) = 1.0;
+    A(1, 4) = 1.0;
+    A(2, 5) = 1.0;
 
-    Eigen::Matrix<Scalar, 6, 6> p_dot = Eigen::Matrix<Scalar, 6, 6>::Zero();
+    Eigen::Matrix<Scalar, 6, 1> x_hat_dot = A * x_hat;
+    x_hat_dot.template block<3, 1>(3, 0) =
+        orientation() * (accel_.cast<Scalar>() - accelerometer_bias_) -
+        Eigen::Vector3d(0, 0, kGravity).cast<Scalar>() * gravity_scalar_;
+
+    // Initialize the position noise to 0.  If the solver is going to back-solve
+    // for the most likely starting position, let's just say that the noise is
+    // small.
+    constexpr double kPositionNoise = 0.0;
+    constexpr double kAccelerometerNoise = 2.3e-6 * 9.8;
+    constexpr double kIMUdt = 5.0e-4;
+    Eigen::Matrix<double, 6, 6> Q_dot(
+        (::Eigen::DiagonalMatrix<double, 6>().diagonal()
+             << ::std::pow(kPositionNoise, 2) / kIMUdt,
+         ::std::pow(kPositionNoise, 2) / kIMUdt,
+         ::std::pow(kPositionNoise, 2) / kIMUdt,
+         ::std::pow(kAccelerometerNoise, 2) / kIMUdt,
+         ::std::pow(kAccelerometerNoise, 2) / kIMUdt,
+         ::std::pow(kAccelerometerNoise, 2) / kIMUdt)
+            .finished()
+            .asDiagonal());
+    Eigen::Matrix<Scalar, 6, 6> p_dot = A.cast<Scalar>() * p +
+                                        p * A.transpose().cast<Scalar>() +
+                                        Q_dot.cast<Scalar>();
 
     return Pack(Eigen::Quaternion<Scalar>(q_dot), x_hat_dot, p_dot);
   }
 
   virtual void ObserveIntegrated(distributed_clock::time_point /*t*/,
                                  Eigen::Matrix<Scalar, 6, 1> /*x_hat*/,
-                                 Eigen::Quaternion<Scalar> /*orientation*/) {}
+                                 Eigen::Quaternion<Scalar> /*orientation*/,
+                                 Eigen::Matrix<Scalar, 6, 6> /*p*/) {}
 
   void Integrate(distributed_clock::time_point t) {
     if (last_time_ != distributed_clock::min_time) {
       Eigen::Matrix<Scalar, 46, 1> next = control_loops::RungeKutta(
-          [this](auto r) { return Derivitive(r); },
+          [this](auto r) { return Derivative(r); },
           Pack(orientation_, x_hat_, p_),
           aos::time::DurationInSeconds(t - last_time_));
 
@@ -189,34 +264,42 @@
     }
 
     last_time_ = t;
-    ObserveIntegrated(t, x_hat_, orientation_);
+    ObserveIntegrated(t, x_hat_, orientation_, p_);
   }
 
   Eigen::Matrix<double, 3, 1> accel_;
   Eigen::Matrix<double, 3, 1> omega_;
   Eigen::Matrix<Scalar, 3, 1> imu_bias_;
 
+  // IMU -> world quaternion
   Eigen::Quaternion<Scalar> orientation_;
   Eigen::Matrix<Scalar, 6, 1> x_hat_;
   Eigen::Matrix<Scalar, 6, 6> p_;
   distributed_clock::time_point last_time_ = distributed_clock::min_time;
 
-  Eigen::Quaternion<Scalar> imu_to_camera_;
+  Eigen::Quaternion<Scalar> imu_to_camera_rotation_;
+  Eigen::Translation<Scalar, 3> imu_to_camera_translation_ =
+      Eigen::Translation3d(0, 0, 0).cast<Scalar>();
 
-  // States outside the KF:
-  //   orientation quaternion
-  //
+  Eigen::Quaternion<Scalar> board_to_world_;
+  Scalar gravity_scalar_;
+  Eigen::Matrix<Scalar, 3, 1> accelerometer_bias_;
   // States:
   //   xyz position
   //   xyz velocity
   //
   // Inputs
   //   xyz accel
-  //   angular rates
   //
   // Measurement:
-  //   xyz position
-  //   orientation rotation vector
+  //   xyz position from camera.
+  //
+  // Since the gyro is so good, we can just solve for the bias and initial
+  // position with the solver and see what it learns.
+
+  // Returns the angular errors for each camera sample.
+  std::vector<Eigen::Matrix<Scalar, 3, 1>> errors_;
+  std::vector<Eigen::Matrix<Scalar, 3, 1>> position_errors_;
 };
 
 // Subclass of the filter above which has plotting.  This keeps debug code and
@@ -225,25 +308,48 @@
  public:
   PoseFilter(Eigen::Quaternion<double> initial_orientation,
              Eigen::Quaternion<double> imu_to_camera,
-             Eigen::Matrix<double, 3, 1> imu_bias)
-      : CeresPoseFilter<double>(initial_orientation, imu_to_camera, imu_bias) {}
+             Eigen::Matrix<double, 3, 1> gyro_bias,
+             Eigen::Matrix<double, 6, 1> initial_state,
+             Eigen::Quaternion<double> board_to_world,
+             Eigen::Matrix<double, 3, 1> imu_to_camera_translation,
+             double gravity_scalar,
+             Eigen::Matrix<double, 3, 1> accelerometer_bias)
+      : CeresPoseFilter<double>(initial_orientation, imu_to_camera, gyro_bias,
+                                initial_state, board_to_world,
+                                imu_to_camera_translation, gravity_scalar,
+                                accelerometer_bias) {}
 
   void Plot() {
+    std::vector<double> rx;
+    std::vector<double> ry;
+    std::vector<double> rz;
     std::vector<double> x;
     std::vector<double> y;
     std::vector<double> z;
+    std::vector<double> vx;
+    std::vector<double> vy;
+    std::vector<double> vz;
     for (const Eigen::Quaternion<double> &q : orientations_) {
       Eigen::Matrix<double, 3, 1> rotation_vector =
           frc971::controls::ToRotationVectorFromQuaternion(q);
-      x.emplace_back(rotation_vector(0, 0));
-      y.emplace_back(rotation_vector(1, 0));
-      z.emplace_back(rotation_vector(2, 0));
+      rx.emplace_back(rotation_vector(0, 0));
+      ry.emplace_back(rotation_vector(1, 0));
+      rz.emplace_back(rotation_vector(2, 0));
     }
+    for (const Eigen::Matrix<double, 6, 1> &x_hat : x_hats_) {
+      x.emplace_back(x_hat(0));
+      y.emplace_back(x_hat(1));
+      z.emplace_back(x_hat(2));
+      vx.emplace_back(x_hat(3));
+      vy.emplace_back(x_hat(4));
+      vz.emplace_back(x_hat(5));
+    }
+
     frc971::analysis::Plotter plotter;
     plotter.AddFigure("position");
-    plotter.AddLine(times_, x, "x_hat(0)");
-    plotter.AddLine(times_, y, "x_hat(1)");
-    plotter.AddLine(times_, z, "x_hat(2)");
+    plotter.AddLine(times_, rx, "x_hat(0)");
+    plotter.AddLine(times_, ry, "x_hat(1)");
+    plotter.AddLine(times_, rz, "x_hat(2)");
     plotter.AddLine(ct, cx, "Camera x");
     plotter.AddLine(ct, cy, "Camera y");
     plotter.AddLine(ct, cz, "Camera z");
@@ -253,9 +359,9 @@
     plotter.Publish();
 
     plotter.AddFigure("error");
-    plotter.AddLine(times_, x, "x_hat(0)");
-    plotter.AddLine(times_, y, "x_hat(1)");
-    plotter.AddLine(times_, z, "x_hat(2)");
+    plotter.AddLine(times_, rx, "x_hat(0)");
+    plotter.AddLine(times_, ry, "x_hat(1)");
+    plotter.AddLine(times_, rz, "x_hat(2)");
     plotter.AddLine(ct, cerrx, "Camera error x");
     plotter.AddLine(ct, cerry, "Camera error y");
     plotter.AddLine(ct, cerrz, "Camera error z");
@@ -268,6 +374,9 @@
     plotter.AddLine(imut, imu_x, "imu x");
     plotter.AddLine(imut, imu_y, "imu y");
     plotter.AddLine(imut, imu_z, "imu z");
+    plotter.AddLine(times_, rx, "rotation x");
+    plotter.AddLine(times_, ry, "rotation y");
+    plotter.AddLine(times_, rz, "rotation z");
     plotter.Publish();
 
     plotter.AddFigure("raw");
@@ -282,12 +391,27 @@
     plotter.AddLine(ct, raw_cz, "Camera z");
     plotter.Publish();
 
+    plotter.AddFigure("xyz vel");
+    plotter.AddLine(times_, x, "x");
+    plotter.AddLine(times_, y, "y");
+    plotter.AddLine(times_, z, "z");
+    plotter.AddLine(times_, vx, "vx");
+    plotter.AddLine(times_, vy, "vy");
+    plotter.AddLine(times_, vz, "vz");
+    plotter.AddLine(ct, camera_position_x, "Camera x");
+    plotter.AddLine(ct, camera_position_y, "Camera y");
+    plotter.AddLine(ct, camera_position_z, "Camera z");
+    plotter.Publish();
+
     plotter.Spin();
   }
 
   void ObserveIntegrated(distributed_clock::time_point t,
                          Eigen::Matrix<double, 6, 1> x_hat,
-                         Eigen::Quaternion<double> orientation) override {
+                         Eigen::Quaternion<double> orientation,
+                         Eigen::Matrix<double, 6, 6> p) override {
+    VLOG(1) << t << " -> " << p;
+    VLOG(1) << t << " xhat -> " << x_hat.transpose();
     times_.emplace_back(chrono::duration<double>(t.time_since_epoch()).count());
     x_hats_.emplace_back(x_hat);
     orientations_.emplace_back(orientation);
@@ -309,18 +433,19 @@
 
   void ObserveCameraUpdate(distributed_clock::time_point t,
                            Eigen::Vector3d board_to_camera_rotation,
-                           Eigen::Quaternion<double> imu_to_world) override {
+                           Eigen::Quaternion<double> imu_to_world_rotation,
+                           Eigen::Affine3d imu_to_world) override {
     raw_cx.emplace_back(board_to_camera_rotation(0, 0));
     raw_cy.emplace_back(board_to_camera_rotation(1, 0));
     raw_cz.emplace_back(board_to_camera_rotation(2, 0));
 
     Eigen::Matrix<double, 3, 1> rotation_vector =
-        frc971::controls::ToRotationVectorFromQuaternion(imu_to_world);
+        frc971::controls::ToRotationVectorFromQuaternion(imu_to_world_rotation);
     ct.emplace_back(chrono::duration<double>(t.time_since_epoch()).count());
 
     Eigen::Matrix<double, 3, 1> cerr =
         frc971::controls::ToRotationVectorFromQuaternion(
-            imu_to_world.inverse() * orientation());
+            imu_to_world_rotation.inverse() * orientation());
 
     cx.emplace_back(rotation_vector(0, 0));
     cy.emplace_back(rotation_vector(1, 0));
@@ -330,11 +455,20 @@
     cerry.emplace_back(cerr(1, 0));
     cerrz.emplace_back(cerr(2, 0));
 
-    const Eigen::Vector3d world_gravity = imu_to_world * last_accel_;
+    const Eigen::Vector3d world_gravity =
+        imu_to_world_rotation * last_accel_ -
+        Eigen::Vector3d(0, 0, kGravity) * gravity_scalar();
+
+    const Eigen::Vector3d camera_position =
+        imu_to_world * Eigen::Vector3d::Zero();
 
     world_gravity_x.emplace_back(world_gravity.x());
     world_gravity_y.emplace_back(world_gravity.y());
     world_gravity_z.emplace_back(world_gravity.z());
+
+    camera_position_x.emplace_back(camera_position.x());
+    camera_position_y.emplace_back(camera_position.y());
+    camera_position_z.emplace_back(camera_position.z());
   }
 
   std::vector<double> ct;
@@ -354,6 +488,9 @@
   std::vector<double> imu_x;
   std::vector<double> imu_y;
   std::vector<double> imu_z;
+  std::vector<double> camera_position_x;
+  std::vector<double> camera_position_y;
+  std::vector<double> camera_position_z;
 
   std::vector<double> imut;
   std::vector<double> imu_ratex;
@@ -375,13 +512,29 @@
 
   template <typename S>
   bool operator()(const S *const q1, const S *const q2, const S *const v,
-                  S *residual) const {
+                  const S *const p, const S *const btw, const S *const itc,
+                  const S *const gravity_scalar_ptr,
+                  const S *const accelerometer_bias_ptr, S *residual) const {
     Eigen::Quaternion<S> initial_orientation(q1[3], q1[0], q1[1], q1[2]);
     Eigen::Quaternion<S> mounting_orientation(q2[3], q2[0], q2[1], q2[2]);
-    Eigen::Matrix<S, 3, 1> imu_bias(v[0], v[1], v[2]);
+    Eigen::Quaternion<S> board_to_world(btw[3], btw[0], btw[1], btw[2]);
+    Eigen::Matrix<S, 3, 1> gyro_bias(v[0], v[1], v[2]);
+    Eigen::Matrix<S, 6, 1> initial_state;
+    initial_state(0) = p[0];
+    initial_state(1) = p[1];
+    initial_state(2) = p[2];
+    initial_state(3) = p[3];
+    initial_state(4) = p[4];
+    initial_state(5) = p[5];
+    Eigen::Matrix<S, 3, 1> imu_to_camera_translation(itc[0], itc[1], itc[2]);
+    Eigen::Matrix<S, 3, 1> accelerometer_bias(accelerometer_bias_ptr[0],
+                                              accelerometer_bias_ptr[1],
+                                              accelerometer_bias_ptr[2]);
 
     CeresPoseFilter<S> filter(initial_orientation, mounting_orientation,
-                              imu_bias);
+                              gyro_bias, initial_state, board_to_world,
+                              imu_to_camera_translation, *gravity_scalar_ptr,
+                              accelerometer_bias);
     data->ReviewData(&filter);
 
     for (size_t i = 0; i < filter.num_errors(); ++i) {
@@ -390,6 +543,12 @@
       residual[3 * i + 2] = filter.errorz(i);
     }
 
+    for (size_t i = 0; i < filter.num_perrors(); ++i) {
+      residual[3 * filter.num_errors() + 3 * i + 0] = filter.errorpx(i);
+      residual[3 * filter.num_errors() + 3 * i + 1] = filter.errorpy(i);
+      residual[3 * filter.num_errors() + 3 * i + 2] = filter.errorpz(i);
+    }
+
     return true;
   }
 };
@@ -437,17 +596,29 @@
   LOG(INFO) << "Done with event_loop running";
   // And now we have it, we can start processing it.
 
-  Eigen::Quaternion<double> nominal_initial_orientation(
+  const Eigen::Quaternion<double> nominal_initial_orientation(
       frc971::controls::ToQuaternionFromRotationVector(
           Eigen::Vector3d(0.0, 0.0, M_PI)));
-  Eigen::Quaternion<double> nominal_imu_to_camera(
+  const Eigen::Quaternion<double> nominal_imu_to_camera(
       Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()));
+  const Eigen::Quaternion<double> nominal_board_to_world(
+      Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX()));
 
-  Eigen::Quaternion<double> initial_orientation =
-      Eigen::Quaternion<double>::Identity();
-  Eigen::Quaternion<double> imu_to_camera =
-      Eigen::Quaternion<double>::Identity();
-  Eigen::Vector3d imu_bias = Eigen::Vector3d::Zero();
+  Eigen::Quaternion<double> initial_orientation = nominal_initial_orientation;
+  // Eigen::Quaternion<double>::Identity();
+  Eigen::Quaternion<double> imu_to_camera = nominal_imu_to_camera;
+  // Eigen::Quaternion<double>::Identity();
+  Eigen::Quaternion<double> board_to_world = nominal_board_to_world;
+  // Eigen::Quaternion<double>::Identity();
+  Eigen::Vector3d gyro_bias = Eigen::Vector3d::Zero();
+  Eigen::Matrix<double, 6, 1> initial_state =
+      Eigen::Matrix<double, 6, 1>::Zero();
+  Eigen::Matrix<double, 3, 1> imu_to_camera_translation =
+      Eigen::Matrix<double, 3, 1>::Zero();
+
+  double gravity_scalar = 1.0;
+  Eigen::Matrix<double, 3, 1> accelerometer_bias =
+      Eigen::Matrix<double, 3, 1>::Zero();
 
   {
     ceres::Problem problem;
@@ -458,19 +629,29 @@
     // auto-differentiation to obtain the derivative (jacobian).
 
     ceres::CostFunction *cost_function =
-        new ceres::AutoDiffCostFunction<CostFunctor, ceres::DYNAMIC, 4, 4, 3>(
-            new CostFunctor(&data), data.camera_samples_size() * 3);
-    problem.AddResidualBlock(cost_function, nullptr,
-                             initial_orientation.coeffs().data(),
-                             imu_to_camera.coeffs().data(), imu_bias.data());
+        new ceres::AutoDiffCostFunction<CostFunctor, ceres::DYNAMIC, 4, 4, 3, 6,
+                                        4, 3, 1, 3>(
+            new CostFunctor(&data), data.camera_samples_size() * 6);
+    problem.AddResidualBlock(
+        cost_function, new ceres::HuberLoss(1.0),
+        initial_orientation.coeffs().data(), imu_to_camera.coeffs().data(),
+        gyro_bias.data(), initial_state.data(), board_to_world.coeffs().data(),
+        imu_to_camera_translation.data(), &gravity_scalar,
+        accelerometer_bias.data());
     problem.SetParameterization(initial_orientation.coeffs().data(),
                                 quaternion_local_parameterization);
     problem.SetParameterization(imu_to_camera.coeffs().data(),
                                 quaternion_local_parameterization);
+    problem.SetParameterization(board_to_world.coeffs().data(),
+                                quaternion_local_parameterization);
     for (int i = 0; i < 3; ++i) {
-      problem.SetParameterLowerBound(imu_bias.data(), i, -0.05);
-      problem.SetParameterUpperBound(imu_bias.data(), i, 0.05);
+      problem.SetParameterLowerBound(gyro_bias.data(), i, -0.05);
+      problem.SetParameterUpperBound(gyro_bias.data(), i, 0.05);
+      problem.SetParameterLowerBound(accelerometer_bias.data(), i, -0.05);
+      problem.SetParameterUpperBound(accelerometer_bias.data(), i, 0.05);
     }
+    problem.SetParameterLowerBound(&gravity_scalar, 0, 0.95);
+    problem.SetParameterUpperBound(&gravity_scalar, 0, 1.05);
 
     // Run the solver!
     ceres::Solver::Options options;
@@ -497,12 +678,30 @@
               << frc971::controls::ToRotationVectorFromQuaternion(
                      imu_to_camera * nominal_imu_to_camera.inverse())
                      .transpose();
-    LOG(INFO) << "imu_bias " << imu_bias.transpose();
+    LOG(INFO) << "gyro_bias " << gyro_bias.transpose();
+    LOG(INFO) << "board_to_world " << board_to_world.coeffs().transpose();
+    LOG(INFO) << "board_to_world(rotation) "
+              << frc971::controls::ToRotationVectorFromQuaternion(
+                     board_to_world)
+                     .transpose();
+    LOG(INFO) << "board_to_world delta "
+              << frc971::controls::ToRotationVectorFromQuaternion(
+                     board_to_world * nominal_board_to_world.inverse())
+                     .transpose();
+    LOG(INFO) << "imu_to_camera_translation "
+              << imu_to_camera_translation.transpose();
+    LOG(INFO) << "gravity " << kGravity * gravity_scalar;
+    LOG(INFO) << "accelerometer bias " << accelerometer_bias.transpose();
   }
 
   {
-    PoseFilter filter(initial_orientation, imu_to_camera, imu_bias);
+    PoseFilter filter(initial_orientation, imu_to_camera, gyro_bias,
+                      initial_state, board_to_world, imu_to_camera_translation,
+                      gravity_scalar, accelerometer_bias);
     data.ReviewData(&filter);
+    if (FLAGS_plot) {
+      filter.Plot();
+    }
   }
 }
 
diff --git a/y2020/vision/sift/sift.fbs b/y2020/vision/sift/sift.fbs
index 3336d0c..0598497 100644
--- a/y2020/vision/sift/sift.fbs
+++ b/y2020/vision/sift/sift.fbs
@@ -104,6 +104,10 @@
 
   // Timestamp for when the calibration was taken on the realtime clock.
   calibration_timestamp:int64 (id: 6);
+
+  // The id of the camera which this calibration data applies to.
+  // Expected to be formatted as Year-Number (YY-##).
+  camera_id:string (id: 7);
 }
 
 // Contains the information the EKF wants from an image matched against a single
diff --git a/y2022/BUILD b/y2022/BUILD
index 67e8587..97d42a1 100644
--- a/y2022/BUILD
+++ b/y2022/BUILD
@@ -28,6 +28,8 @@
     binaries = [
         "//y2020/vision:calibration",
         "//y2022/vision:viewer",
+        "//y2022/localizer:imu_main",
+        "//y2022/control_loops/localizer:localizer_main",
     ],
     data = [
         ":config",
@@ -57,6 +59,7 @@
     target_compatible_with = ["@platforms//os:linux"],
     visibility = ["//visibility:public"],
     deps = [
+        ":config_imu",
         ":config_logger",
         ":config_pi1",
         ":config_pi2",
@@ -98,6 +101,25 @@
 ]
 
 aos_config(
+    name = "config_imu",
+    src = "y2022_imu.json",
+    flatbuffers = [
+        "//aos/network:message_bridge_client_fbs",
+        "//aos/network:message_bridge_server_fbs",
+        "//aos/network:timestamp_fbs",
+        "//aos/network:remote_message_fbs",
+        "//y2022/control_loops/localizer:localizer_status_fbs",
+        "//y2022/control_loops/localizer:localizer_output_fbs",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+    deps = [
+        "//aos/events:config",
+        "//frc971/control_loops/drivetrain:config",
+    ],
+)
+
+aos_config(
     name = "config_logger",
     src = "y2022_logger.json",
     flatbuffers = [
@@ -167,6 +189,7 @@
         "//frc971/control_loops:pose",
         "//frc971/control_loops:static_zeroing_single_dof_profiled_subsystem",
         "//y2022/control_loops/drivetrain:polydrivetrain_plants",
+        "//y2022/control_loops/superstructure/intake:intake_plants",
         "@com_github_google_glog//:glog",
         "@com_google_absl//absl/base",
     ],
@@ -233,3 +256,10 @@
         "//y2022/control_loops/superstructure:superstructure_status_fbs",
     ],
 )
+
+py_library(
+    name = "python_init",
+    srcs = ["__init__.py"],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+)
diff --git a/y2022/__init__.py b/y2022/__init__.py
new file mode 100644
index 0000000..e69de29
--- /dev/null
+++ b/y2022/__init__.py
diff --git a/y2022/constants.cc b/y2022/constants.cc
index 98f6511..73e72f3 100644
--- a/y2022/constants.cc
+++ b/y2022/constants.cc
@@ -11,6 +11,7 @@
 #include "aos/mutex/mutex.h"
 #include "aos/network/team_number.h"
 #include "glog/logging.h"
+#include "y2022/control_loops/superstructure/intake/integral_intake_plant.h"
 
 namespace y2022 {
 namespace constants {
@@ -26,6 +27,37 @@
 const Values *DoGetValuesForTeam(uint16_t team) {
   Values *const r = new Values();
 
+  // TODO(Yash): Set constants
+  // Intake constants.
+  auto *const intake = &r->intake;
+
+  intake->zeroing_voltage = 3.0;
+  intake->operating_voltage = 12.0;
+  intake->zeroing_profile_params = {0.5, 3.0};
+  intake->default_profile_params = {6.0, 30.0};
+  intake->range = Values::kIntakeRange();
+  intake->make_integral_loop =
+      control_loops::superstructure::intake::MakeIntegralIntakeLoop;
+
+  // The number of samples in the moving average filter.
+  intake->zeroing_constants.average_filter_size = Values::kZeroingSampleSize;
+  // The distance that the absolute encoder needs to complete a full rotation.
+  intake->zeroing_constants.one_revolution_distance =
+      M_PI * 2.0 * constants::Values::kIntakeEncoderRatio();
+
+  // Threshold for deciding if we are moving. moving_buffer_size samples need to
+  // be within this distance of each other before we use the middle one to zero.
+  intake->zeroing_constants.zeroing_threshold = 0.0005;
+  // Buffer size for deciding if we are moving.
+  intake->zeroing_constants.moving_buffer_size = 20;
+
+  // Value between 0 and 1 indicating what fraction of one_revolution_distance
+  // it is acceptable for the offset to move.
+  intake->zeroing_constants.allowable_encoder_error = 0.9;
+
+  // Measured absolute position of the encoder when at zero.
+  intake->zeroing_constants.measured_absolute_position = 0.0;
+
   switch (team) {
     // A set of constants for tests.
     case 1:
diff --git a/y2022/constants.h b/y2022/constants.h
index 050a363..92f3a48 100644
--- a/y2022/constants.h
+++ b/y2022/constants.h
@@ -9,6 +9,7 @@
 #include "frc971/control_loops/pose.h"
 #include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h"
 #include "y2022/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+#include "y2022/control_loops/superstructure/intake/intake_plant.h"
 
 namespace y2022 {
 namespace constants {
@@ -29,9 +30,31 @@
            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;
+  }
+
   static constexpr double kRollerSupplyCurrentLimit() { return 30.0; }
   static constexpr double kRollerStatorCurrentLimit() { return 40.0; }
 
+  ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemParams<
+      ::frc971::zeroing::PotAndAbsoluteEncoderZeroingEstimator>
+      intake;
+
+  // TODO (Yash): Constants need to be tuned
+  static constexpr ::frc971::constants::Range kIntakeRange() {
+    return ::frc971::constants::Range{
+        .lower_hard = -0.5,         // Back Hard
+        .upper_hard = 2.85 + 0.05,  // Front Hard
+        .lower = -0.300,            // Back Soft
+        .upper = 2.725              // Front Soft
+    };
+  }
   // Climber
   static constexpr double kClimberSupplyCurrentLimit() { return 60.0; }
 
diff --git a/y2022/control_loops/BUILD b/y2022/control_loops/BUILD
new file mode 100644
index 0000000..49bc419
--- /dev/null
+++ b/y2022/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:python_init"],
+)
diff --git a/y2022/control_loops/__init__.py b/y2022/control_loops/__init__.py
new file mode 100644
index 0000000..e69de29
--- /dev/null
+++ b/y2022/control_loops/__init__.py
diff --git a/y2022/control_loops/drivetrain/BUILD b/y2022/control_loops/drivetrain/BUILD
index 2858dc7..a1f1e47 100644
--- a/y2022/control_loops/drivetrain/BUILD
+++ b/y2022/control_loops/drivetrain/BUILD
@@ -1,3 +1,5 @@
+load("//aos:config.bzl", "aos_config")
+
 genrule(
     name = "genrule_drivetrain",
     outs = [
@@ -69,6 +71,19 @@
     ],
 )
 
+cc_library(
+    name = "localizer",
+    srcs = ["localizer.cc"],
+    hdrs = ["localizer.h"],
+    deps = [
+        "//aos/events:event_loop",
+        "//aos/network:message_bridge_server_fbs",
+        "//frc971/control_loops/drivetrain:hybrid_ekf",
+        "//frc971/control_loops/drivetrain:localizer",
+        "//y2022/control_loops/localizer:localizer_output_fbs",
+    ],
+)
+
 cc_binary(
     name = "drivetrain",
     srcs = [
@@ -78,8 +93,40 @@
     visibility = ["//visibility:public"],
     deps = [
         ":drivetrain_base",
+        ":localizer",
         "//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:config",
+    ],
+)
+
+cc_test(
+    name = "localizer_test",
+    srcs = ["localizer_test.cc"],
+    data = [":simulation_config"],
+    target_compatible_with = ["@platforms//os:linux"],
+    deps = [
+        ":drivetrain_base",
+        ":localizer",
+        "//aos/events:simulated_event_loop",
+        "//aos/events/logging:log_writer",
+        "//aos/network:team_number",
+        "//aos/network:testing_time_converter",
+        "//frc971/control_loops:control_loop_test",
+        "//frc971/control_loops:team_number_test_environment",
+        "//frc971/control_loops/drivetrain:drivetrain_lib",
+        "//frc971/control_loops/drivetrain:drivetrain_test_lib",
+        "//y2022/control_loops/localizer:localizer_output_fbs",
+    ],
+)
diff --git a/y2022/control_loops/drivetrain/drivetrain_base.cc b/y2022/control_loops/drivetrain/drivetrain_base.cc
index cbc9c42..93233d2 100644
--- a/y2022/control_loops/drivetrain/drivetrain_base.cc
+++ b/y2022/control_loops/drivetrain/drivetrain_base.cc
@@ -25,7 +25,7 @@
   static DrivetrainConfig<double> kDrivetrainConfig{
       ::frc971::control_loops::drivetrain::ShifterType::SIMPLE_SHIFTER,
       ::frc971::control_loops::drivetrain::LoopType::CLOSED_LOOP,
-      ::frc971::control_loops::drivetrain::GyroType::IMU_Z_GYRO,
+      ::frc971::control_loops::drivetrain::GyroType::SPARTAN_GYRO,
       ::frc971::control_loops::drivetrain::IMUType::IMU_FLIPPED_X,
 
       drivetrain::MakeDrivetrainLoop,
diff --git a/y2022/control_loops/drivetrain/drivetrain_main.cc b/y2022/control_loops/drivetrain/drivetrain_main.cc
index e29f950..ecdcdbb 100644
--- a/y2022/control_loops/drivetrain/drivetrain_main.cc
+++ b/y2022/control_loops/drivetrain/drivetrain_main.cc
@@ -4,6 +4,7 @@
 #include "aos/init.h"
 #include "frc971/control_loops/drivetrain/drivetrain.h"
 #include "y2022/control_loops/drivetrain/drivetrain_base.h"
+#include "y2022/control_loops/drivetrain/localizer.h"
 
 using ::frc971::control_loops::drivetrain::DrivetrainLoop;
 
@@ -14,7 +15,7 @@
       aos::configuration::ReadConfig("config.json");
 
   ::aos::ShmEventLoop event_loop(&config.message());
-  ::frc971::control_loops::drivetrain::DeadReckonEkf localizer(
+  ::y2022::control_loops::drivetrain::Localizer localizer(
       &event_loop,
       ::y2022::control_loops::drivetrain::GetDrivetrainConfig());
   std::unique_ptr<DrivetrainLoop> drivetrain = std::make_unique<DrivetrainLoop>(
diff --git a/y2022/control_loops/drivetrain/drivetrain_simulation_config.json b/y2022/control_loops/drivetrain/drivetrain_simulation_config.json
new file mode 100644
index 0000000..37c1bb7
--- /dev/null
+++ b/y2022/control_loops/drivetrain/drivetrain_simulation_config.json
@@ -0,0 +1,6 @@
+{
+  "imports": [
+    "../../y2022.json",
+    "../../../frc971/control_loops/drivetrain/drivetrain_simulation_channels.json"
+  ]
+}
diff --git a/y2022/control_loops/drivetrain/localizer.cc b/y2022/control_loops/drivetrain/localizer.cc
new file mode 100644
index 0000000..3d02312
--- /dev/null
+++ b/y2022/control_loops/drivetrain/localizer.cc
@@ -0,0 +1,102 @@
+#include "y2022/control_loops/drivetrain/localizer.h"
+
+namespace y2022 {
+namespace control_loops {
+namespace drivetrain {
+
+Localizer::Localizer(
+    aos::EventLoop *event_loop,
+    const frc971::control_loops::drivetrain::DrivetrainConfig<double>
+        &dt_config)
+    : event_loop_(event_loop),
+      dt_config_(dt_config),
+      ekf_(dt_config),
+      localizer_output_fetcher_(
+          event_loop_->MakeFetcher<frc971::controls::LocalizerOutput>(
+              "/localizer")),
+      clock_offset_fetcher_(
+          event_loop_->MakeFetcher<aos::message_bridge::ServerStatistics>(
+              "/aos")) {
+  ekf_.set_ignore_accel(true);
+
+  event_loop->OnRun([this, event_loop]() {
+    ekf_.ResetInitialState(event_loop->monotonic_now(),
+                           HybridEkf::State::Zero(), ekf_.P());
+  });
+
+  target_selector_.set_has_target(false);
+}
+
+void Localizer::Reset(
+    aos::monotonic_clock::time_point t,
+    const frc971::control_loops::drivetrain::HybridEkf<double>::State &state) {
+  // Go through and clear out all of the fetchers so that we don't get behind.
+  localizer_output_fetcher_.Fetch();
+  ekf_.ResetInitialState(t, state.cast<float>(), ekf_.P());
+}
+
+void Localizer::Update(const Eigen::Matrix<double, 2, 1> &U,
+                       aos::monotonic_clock::time_point now,
+                       double left_encoder, double right_encoder,
+                       double gyro_rate, const Eigen::Vector3d &accel) {
+  ekf_.UpdateEncodersAndGyro(left_encoder, right_encoder, gyro_rate,
+                             U.cast<float>(), accel.cast<float>(), now);
+  if (localizer_output_fetcher_.Fetch()) {
+    clock_offset_fetcher_.Fetch();
+    bool message_bridge_connected = true;
+    std::chrono::nanoseconds monotonic_offset{0};
+    if (clock_offset_fetcher_.get() != nullptr) {
+      for (const auto connection : *clock_offset_fetcher_->connections()) {
+        if (connection->has_node() && connection->node()->has_name() &&
+            connection->node()->name()->string_view() == "imu") {
+          if (connection->has_monotonic_offset()) {
+            monotonic_offset =
+                std::chrono::nanoseconds(connection->monotonic_offset());
+          } else {
+            // If we don't have a monotonic offset, that means we aren't
+            // connected, in which case we should break the loop but shouldn't
+            // populate the offset.
+            message_bridge_connected = false;
+          }
+          break;
+        }
+      }
+    }
+    if (!message_bridge_connected) {
+      return;
+    }
+    aos::monotonic_clock::time_point capture_time(
+        std::chrono::nanoseconds(
+            localizer_output_fetcher_->monotonic_timestamp_ns()) -
+        monotonic_offset);
+    // TODO: Finish implementing simple x/y/theta updater with state_at_capture.
+    // TODO: Implement turret/camera processing logic on pi side.
+    const std::optional<State> state_at_capture =
+        ekf_.LastStateBeforeTime(capture_time);
+    Eigen::Matrix<float, HybridEkf::kNOutputs, HybridEkf::kNStates> H;
+    H.setZero();
+    H(0, StateIdx::kX) = 1;
+    H(1, StateIdx::kY) = 1;
+    H(2, StateIdx::kTheta) = 1;
+    const Eigen::Vector3f Z{
+        static_cast<float>(localizer_output_fetcher_->x()),
+        static_cast<float>(localizer_output_fetcher_->y()),
+        static_cast<float>(localizer_output_fetcher_->theta())};
+    Eigen::Matrix3f R = Eigen::Matrix3f::Zero();
+    R.diagonal() << 0.01, 0.01, 1e-4;
+    const Input U_correct = ekf_.MostRecentInput();
+    ekf_.Correct(
+        Eigen::Vector3f::Zero(), &U_correct, {},
+        [H, state_at_capture, Z](const State &,
+                                 const Input &) -> Eigen::Vector3f {
+          Eigen::Vector3f error = H * state_at_capture.value() - Z;
+          error(2) = aos::math::NormalizeAngle(error(2));
+          return error;
+        },
+        [H](const State &) { return H; }, R, now);
+  }
+}
+
+}  // namespace drivetrain
+}  // namespace control_loops
+}  // namespace y2022
diff --git a/y2022/control_loops/drivetrain/localizer.h b/y2022/control_loops/drivetrain/localizer.h
new file mode 100644
index 0000000..50d083a
--- /dev/null
+++ b/y2022/control_loops/drivetrain/localizer.h
@@ -0,0 +1,80 @@
+#ifndef Y2022_CONTROL_LOOPS_DRIVETRAIN_LOCALIZER_H_
+#define Y2022_CONTROL_LOOPS_DRIVETRAIN_LOCALIZER_H_
+
+#include <string_view>
+
+#include "aos/events/event_loop.h"
+#include "frc971/control_loops/drivetrain/hybrid_ekf.h"
+#include "frc971/control_loops/drivetrain/localizer.h"
+#include "y2022/control_loops/localizer/localizer_output_generated.h"
+#include "aos/network/message_bridge_server_generated.h"
+
+namespace y2022 {
+namespace control_loops {
+namespace drivetrain {
+
+// This class handles the localization for the 2022 robot. Rather than actually
+// doing any work on the roborio, we farm all the localization out to a
+// raspberry pi and it then sends out LocalizerOutput messages that we treat as
+// measurement updates. See //y2022/control_loops/localizer.
+// TODO(james): Needs tests. Should refactor out some of the code from the 2020
+// localizer test.
+class Localizer : public frc971::control_loops::drivetrain::LocalizerInterface {
+ public:
+  typedef frc971::control_loops::TypedPose<float> Pose;
+  typedef frc971::control_loops::drivetrain::HybridEkf<float> HybridEkf;
+  typedef typename HybridEkf::State State;
+  typedef typename HybridEkf::StateIdx StateIdx;
+  typedef typename HybridEkf::StateSquare StateSquare;
+  typedef typename HybridEkf::Input Input;
+  typedef typename HybridEkf::Output Output;
+  Localizer(aos::EventLoop *event_loop,
+            const frc971::control_loops::drivetrain::DrivetrainConfig<double>
+                &dt_config);
+  frc971::control_loops::drivetrain::HybridEkf<double>::State Xhat()
+      const override {
+    return ekf_.X_hat().cast<double>();
+  }
+  frc971::control_loops::drivetrain::TrivialTargetSelector *target_selector()
+      override {
+    return &target_selector_;
+  }
+
+  void Update(const ::Eigen::Matrix<double, 2, 1> &U,
+              aos::monotonic_clock::time_point now, double left_encoder,
+              double right_encoder, double gyro_rate,
+              const Eigen::Vector3d &accel) override;
+
+  void Reset(aos::monotonic_clock::time_point t,
+             const frc971::control_loops::drivetrain::HybridEkf<double>::State
+                 &state) override;
+
+  void ResetPosition(aos::monotonic_clock::time_point t, double x, double y,
+                     double theta, double /*theta_override*/,
+                     bool /*reset_theta*/) override {
+    const double left_encoder = ekf_.X_hat(StateIdx::kLeftEncoder);
+    const double right_encoder = ekf_.X_hat(StateIdx::kRightEncoder);
+    ekf_.ResetInitialState(t,
+                           (HybridEkf::State() << x, y, theta, left_encoder, 0,
+                            right_encoder, 0, 0, 0, 0, 0, 0)
+                               .finished(),
+                           ekf_.P());
+  }
+
+ private:
+  aos::EventLoop *const event_loop_;
+  const frc971::control_loops::drivetrain::DrivetrainConfig<double> dt_config_;
+  HybridEkf ekf_;
+
+  aos::Fetcher<frc971::controls::LocalizerOutput> localizer_output_fetcher_;
+  aos::Fetcher<aos::message_bridge::ServerStatistics> clock_offset_fetcher_;
+
+  // Target selector to allow us to satisfy the LocalizerInterface requirements.
+  frc971::control_loops::drivetrain::TrivialTargetSelector target_selector_;
+};
+
+}  // namespace drivetrain
+}  // namespace control_loops
+}  // namespace y2022
+
+#endif  // Y2022_CONTROL_LOOPS_DRIVETRAIN_LOCALIZER_H_
diff --git a/y2022/control_loops/drivetrain/localizer_test.cc b/y2022/control_loops/drivetrain/localizer_test.cc
new file mode 100644
index 0000000..87fc3fd
--- /dev/null
+++ b/y2022/control_loops/drivetrain/localizer_test.cc
@@ -0,0 +1,208 @@
+#include "y2022/control_loops/drivetrain/localizer.h"
+
+#include <queue>
+
+#include "aos/events/logging/log_writer.h"
+#include "aos/network/message_bridge_server_generated.h"
+#include "aos/network/team_number.h"
+#include "aos/network/testing_time_converter.h"
+#include "frc971/control_loops/control_loop_test.h"
+#include "frc971/control_loops/drivetrain/drivetrain.h"
+#include "frc971/control_loops/drivetrain/drivetrain_test_lib.h"
+#include "frc971/control_loops/team_number_test_environment.h"
+#include "y2022/control_loops/localizer/localizer_output_generated.h"
+#include "gtest/gtest.h"
+#include "y2022/control_loops/drivetrain/drivetrain_base.h"
+
+DEFINE_string(output_folder, "",
+              "If set, logs all channels to the provided logfile.");
+
+namespace y2022 {
+namespace control_loops {
+namespace drivetrain {
+namespace testing {
+
+using frc971::control_loops::drivetrain::DrivetrainConfig;
+using frc971::control_loops::drivetrain::Goal;
+using frc971::control_loops::drivetrain::LocalizerControl;
+
+namespace {
+DrivetrainConfig<double> GetTest2022DrivetrainConfig() {
+  DrivetrainConfig<double> config = GetDrivetrainConfig();
+  return config;
+}
+}
+
+namespace chrono = std::chrono;
+using aos::monotonic_clock;
+using frc971::control_loops::drivetrain::DrivetrainLoop;
+using frc971::control_loops::drivetrain::testing::DrivetrainSimulation;
+
+// TODO(james): Make it so this actually tests the full system of the localizer.
+class LocalizedDrivetrainTest : public frc971::testing::ControlLoopTest {
+ protected:
+  // We must use the 2022 drivetrain config so that we don't have to deal
+  // with shifting:
+  LocalizedDrivetrainTest()
+      : frc971::testing::ControlLoopTest(
+            aos::configuration::ReadConfig(
+                "y2022/control_loops/drivetrain/simulation_config.json"),
+            GetTest2022DrivetrainConfig().dt),
+        roborio_(aos::configuration::GetNode(configuration(), "roborio")),
+        imu_(aos::configuration::GetNode(configuration(), "imu")),
+        test_event_loop_(MakeEventLoop("test", roborio_)),
+        imu_test_event_loop_(MakeEventLoop("test", imu_)),
+        drivetrain_goal_sender_(
+            test_event_loop_->MakeSender<Goal>("/drivetrain")),
+        localizer_output_sender_(
+            imu_test_event_loop_->MakeSender<frc971::controls::LocalizerOutput>(
+                "/localizer")),
+        drivetrain_goal_fetcher_(
+            test_event_loop_->MakeFetcher<Goal>("/drivetrain")),
+        drivetrain_status_fetcher_(
+            test_event_loop_
+                ->MakeFetcher<frc971::control_loops::drivetrain::Status>(
+                    "/drivetrain")),
+        localizer_control_sender_(
+            test_event_loop_->MakeSender<LocalizerControl>("/drivetrain")),
+        drivetrain_event_loop_(MakeEventLoop("drivetrain", roborio_)),
+        dt_config_(GetTest2022DrivetrainConfig()),
+        localizer_(drivetrain_event_loop_.get(), dt_config_),
+        drivetrain_(dt_config_, drivetrain_event_loop_.get(), &localizer_),
+        drivetrain_plant_event_loop_(MakeEventLoop("plant", roborio_)),
+        drivetrain_plant_imu_event_loop_(MakeEventLoop("plant", imu_)),
+        drivetrain_plant_(drivetrain_plant_event_loop_.get(),
+                          drivetrain_plant_imu_event_loop_.get(), dt_config_,
+                          std::chrono::microseconds(500)) {
+    set_team_id(frc971::control_loops::testing::kTeamNumber);
+    set_battery_voltage(12.0);
+
+    if (!FLAGS_output_folder.empty()) {
+      logger_event_loop_ = MakeEventLoop("logger", roborio_);
+      logger_ = std::make_unique<aos::logger::Logger>(logger_event_loop_.get());
+      logger_->StartLoggingOnRun(FLAGS_output_folder);
+    }
+
+    test_event_loop_->OnRun([this]() { SetStartingPosition({3.0, 2.0, 0.0}); });
+
+    imu_test_event_loop_
+        ->AddTimer([this]() {
+          auto builder = localizer_output_sender_.MakeBuilder();
+          frc971::controls::LocalizerOutput::Builder output_builder =
+              builder.MakeBuilder<frc971::controls::LocalizerOutput>();
+          output_builder.add_monotonic_timestamp_ns(
+              imu_test_event_loop_->monotonic_now().time_since_epoch().count());
+          output_builder.add_x(drivetrain_plant_.state()(0));
+          output_builder.add_y(drivetrain_plant_.state()(1));
+          output_builder.add_theta(drivetrain_plant_.state()(2));
+        })
+        ->Setup(imu_test_event_loop_->monotonic_now(),
+                std::chrono::milliseconds(5));
+  }
+
+  virtual ~LocalizedDrivetrainTest() override {}
+
+  void SetStartingPosition(const Eigen::Matrix<double, 3, 1> &xytheta) {
+    *drivetrain_plant_.mutable_state() << xytheta.x(), xytheta.y(),
+        xytheta(2, 0), 0.0, 0.0;
+    Eigen::Matrix<double, Localizer::HybridEkf::kNStates, 1> localizer_state;
+    localizer_state.setZero();
+    localizer_state.block<3, 1>(0, 0) = xytheta;
+    localizer_.Reset(monotonic_now(), localizer_state);
+  }
+
+  void VerifyNearGoal(double eps = 1e-2) {
+    drivetrain_goal_fetcher_.Fetch();
+    EXPECT_NEAR(drivetrain_goal_fetcher_->left_goal(),
+                drivetrain_plant_.GetLeftPosition(), eps);
+    EXPECT_NEAR(drivetrain_goal_fetcher_->right_goal(),
+                drivetrain_plant_.GetRightPosition(), eps);
+  }
+
+  ::testing::AssertionResult IsNear(double expected, double actual,
+                                    double epsilon) {
+    if (std::abs(expected - actual) < epsilon) {
+      return ::testing::AssertionSuccess();
+    } else {
+      return ::testing::AssertionFailure()
+             << "Expected " << expected << " but got " << actual
+             << " with a max difference of " << epsilon
+             << " and an actual difference of " << std::abs(expected - actual);
+    }
+  }
+  ::testing::AssertionResult VerifyEstimatorAccurate(double eps) {
+    const Eigen::Matrix<double, 5, 1> true_state = drivetrain_plant_.state();
+    ::testing::AssertionResult result(true);
+    if (!(result = IsNear(localizer_.x(), true_state(0), eps))) {
+      return result;
+    }
+    if (!(result = IsNear(localizer_.y(), true_state(1), eps))) {
+      return result;
+    }
+    if (!(result = IsNear(localizer_.theta(), true_state(2), eps))) {
+      return result;
+    }
+    if (!(result = IsNear(localizer_.left_velocity(), true_state(3), eps))) {
+      return result;
+    }
+    if (!(result = IsNear(localizer_.right_velocity(), true_state(4), eps))) {
+      return result;
+    }
+    return result;
+  }
+
+  const aos::Node *const roborio_;
+  const aos::Node *const imu_;
+
+  std::unique_ptr<aos::EventLoop> test_event_loop_;
+  std::unique_ptr<aos::EventLoop> imu_test_event_loop_;
+  aos::Sender<Goal> drivetrain_goal_sender_;
+  aos::Sender<frc971::controls::LocalizerOutput> localizer_output_sender_;
+  aos::Fetcher<Goal> drivetrain_goal_fetcher_;
+  aos::Fetcher<frc971::control_loops::drivetrain::Status>
+      drivetrain_status_fetcher_;
+  aos::Sender<LocalizerControl> localizer_control_sender_;
+
+  std::unique_ptr<aos::EventLoop> drivetrain_event_loop_;
+  const frc971::control_loops::drivetrain::DrivetrainConfig<double> dt_config_;
+
+  Localizer localizer_;
+  DrivetrainLoop drivetrain_;
+
+  std::unique_ptr<aos::EventLoop> drivetrain_plant_event_loop_;
+  std::unique_ptr<aos::EventLoop> drivetrain_plant_imu_event_loop_;
+  DrivetrainSimulation drivetrain_plant_;
+
+  void SendGoal(double left, double right) {
+    auto builder = drivetrain_goal_sender_.MakeBuilder();
+
+    Goal::Builder drivetrain_builder = builder.MakeBuilder<Goal>();
+    drivetrain_builder.add_controller_type(
+        frc971::control_loops::drivetrain::ControllerType::MOTION_PROFILE);
+    drivetrain_builder.add_left_goal(left);
+    drivetrain_builder.add_right_goal(right);
+
+    EXPECT_EQ(builder.Send(drivetrain_builder.Finish()),
+              aos::RawSender::Error::kOk);
+  }
+
+ private:
+  std::unique_ptr<aos::EventLoop> logger_event_loop_;
+  std::unique_ptr<aos::logger::Logger> logger_;
+};
+
+TEST_F(LocalizedDrivetrainTest, Nominal) {
+  SetEnabled(true);
+  EXPECT_TRUE(VerifyEstimatorAccurate(1e-7));
+
+  SendGoal(-1.0, 1.0);
+
+  RunFor(chrono::seconds(10));
+  VerifyNearGoal();
+  EXPECT_TRUE(VerifyEstimatorAccurate(5e-3));
+}
+
+}  // namespace testing
+}  // namespace drivetrain
+}  // namespace control_loops
+}  // namespace y2022
diff --git a/y2022/control_loops/localizer/BUILD b/y2022/control_loops/localizer/BUILD
new file mode 100644
index 0000000..034c779
--- /dev/null
+++ b/y2022/control_loops/localizer/BUILD
@@ -0,0 +1,119 @@
+load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
+load("//aos:flatbuffers.bzl", "cc_static_flatbuffer")
+load("@npm//@bazel/typescript:index.bzl", "ts_library")
+
+ts_library(
+    name = "localizer_plotter",
+    srcs = ["localizer_plotter.ts"],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+    deps = [
+        "//aos/network/www:aos_plotter",
+        "//aos/network/www:colors",
+        "//aos/network/www:proxy",
+        "//frc971/wpilib:imu_plot_utils",
+    ],
+)
+
+flatbuffer_cc_library(
+    name = "localizer_output_fbs",
+    srcs = [
+        "localizer_output.fbs",
+    ],
+    gen_reflections = True,
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+)
+
+flatbuffer_cc_library(
+    name = "localizer_status_fbs",
+    srcs = [
+        "localizer_status.fbs",
+    ],
+    gen_reflections = True,
+    includes = [
+        "//frc971/control_loops:control_loops_fbs_includes",
+        "//frc971/control_loops/drivetrain:drivetrain_status_fbs_includes",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+)
+
+cc_static_flatbuffer(
+    name = "localizer_schema",
+    function = "frc971::controls::LocalizerStatusSchema",
+    target = ":localizer_status_fbs_reflection_out",
+    visibility = ["//visibility:public"],
+)
+
+cc_library(
+    name = "localizer",
+    srcs = ["localizer.cc"],
+    hdrs = ["localizer.h"],
+    visibility = ["//visibility:public"],
+    deps = [
+        ":localizer_output_fbs",
+        ":localizer_status_fbs",
+        "//aos/containers:ring_buffer",
+        "//aos/events:event_loop",
+        "//aos/time",
+        "//frc971/control_loops:c2d",
+        "//frc971/control_loops:control_loops_fbs",
+        "//frc971/control_loops/drivetrain:drivetrain_output_fbs",
+        "//frc971/control_loops/drivetrain:drivetrain_status_fbs",
+        "//frc971/control_loops/drivetrain:improved_down_estimator",
+        "//frc971/control_loops/drivetrain:localizer_fbs",
+        "//frc971/wpilib:imu_batch_fbs",
+        "//frc971/wpilib:imu_fbs",
+        "//frc971/zeroing:imu_zeroer",
+        "//y2020/vision/sift:sift_fbs",
+        "@org_tuxfamily_eigen//:eigen",
+    ],
+)
+
+cc_binary(
+    name = "localizer_main",
+    srcs = ["localizer_main.cc"],
+    visibility = ["//visibility:public"],
+    deps = [
+        ":localizer",
+        "//aos:init",
+        "//aos/events:shm_event_loop",
+        "//y2022/control_loops/drivetrain:drivetrain_base",
+    ],
+)
+
+cc_test(
+    name = "localizer_test",
+    srcs = ["localizer_test.cc"],
+    data = [
+        "//y2022:config",
+    ],
+    shard_count = 10,
+    deps = [
+        ":localizer",
+        "//aos/events:simulated_event_loop",
+        "//aos/testing:googletest",
+        "//frc971/control_loops/drivetrain:drivetrain_test_lib",
+    ],
+)
+
+cc_binary(
+    name = "localizer_replay",
+    srcs = ["localizer_replay.cc"],
+    data = [
+        "//y2020:config",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    deps = [
+        ":localizer",
+        ":localizer_schema",
+        "//aos:configuration",
+        "//aos:init",
+        "//aos:json_to_flatbuffer",
+        "//aos/events:simulated_event_loop",
+        "//aos/events/logging:log_reader",
+        "//aos/events/logging:log_writer",
+        "//y2020/control_loops/drivetrain:drivetrain_base",
+    ],
+)
diff --git a/y2022/control_loops/localizer/localizer.cc b/y2022/control_loops/localizer/localizer.cc
new file mode 100644
index 0000000..3c68e59
--- /dev/null
+++ b/y2022/control_loops/localizer/localizer.cc
@@ -0,0 +1,571 @@
+#include "y2022/control_loops/localizer/localizer.h"
+
+#include "frc971/control_loops/c2d.h"
+#include "frc971/wpilib/imu_batch_generated.h"
+// TODO(james): Things to do:
+// -Approach still seems fundamentally sound.
+// -Really need to work on cost/residual function.
+//    -Particularly for handling stopping.
+//    -Extra hysteresis
+
+namespace frc971::controls {
+
+namespace {
+constexpr double kG = 9.80665;
+constexpr std::chrono::microseconds kNominalDt(500);
+
+template <int N>
+Eigen::Matrix<double, N, 1> MakeState(std::vector<double> values) {
+  CHECK_EQ(static_cast<size_t>(N), values.size());
+  Eigen::Matrix<double, N, 1> vector;
+  for (int ii = 0; ii < N; ++ii) {
+    vector(ii, 0) = values[ii];
+  }
+  return vector;
+}
+}  // namespace
+
+ModelBasedLocalizer::ModelBasedLocalizer(
+    const control_loops::drivetrain::DrivetrainConfig<double> &dt_config)
+    : dt_config_(dt_config),
+      velocity_drivetrain_coefficients_(
+          dt_config.make_hybrid_drivetrain_velocity_loop()
+              .plant()
+              .coefficients()),
+      down_estimator_(dt_config) {
+  CHECK_EQ(branches_.capacity(), static_cast<size_t>(std::chrono::seconds(1) /
+                                                 kNominalDt / kBranchPeriod));
+  if (dt_config_.is_simulated) {
+    down_estimator_.assume_perfect_gravity();
+  }
+  A_continuous_accel_.setZero();
+  A_continuous_model_.setZero();
+  B_continuous_accel_.setZero();
+  B_continuous_model_.setZero();
+
+  A_continuous_accel_(kX, kVelocityX) = 1.0;
+  A_continuous_accel_(kY, kVelocityY) = 1.0;
+
+  const double diameter = 2.0 * dt_config_.robot_radius;
+
+  A_continuous_model_(kTheta, kLeftVelocity) = -1.0 / diameter;
+  A_continuous_model_(kTheta, kRightVelocity) = 1.0 / diameter;
+  A_continuous_model_(kLeftEncoder, kLeftVelocity) = 1.0;
+  A_continuous_model_(kRightEncoder, kRightVelocity) = 1.0;
+  const auto &vel_coefs = velocity_drivetrain_coefficients_;
+  A_continuous_model_(kLeftVelocity, kLeftVelocity) =
+      vel_coefs.A_continuous(0, 0);
+  A_continuous_model_(kLeftVelocity, kRightVelocity) =
+      vel_coefs.A_continuous(0, 1);
+  A_continuous_model_(kRightVelocity, kLeftVelocity) =
+      vel_coefs.A_continuous(1, 0);
+  A_continuous_model_(kRightVelocity, kRightVelocity) =
+      vel_coefs.A_continuous(1, 1);
+
+  A_continuous_model_(kLeftVelocity, kLeftVoltageError) =
+      1 * vel_coefs.B_continuous(0, 0);
+  A_continuous_model_(kLeftVelocity, kRightVoltageError) =
+      1 * vel_coefs.B_continuous(0, 1);
+  A_continuous_model_(kRightVelocity, kLeftVoltageError) =
+      1 * vel_coefs.B_continuous(1, 0);
+  A_continuous_model_(kRightVelocity, kRightVoltageError) =
+      1 * vel_coefs.B_continuous(1, 1);
+
+  B_continuous_model_.block<1, 2>(kLeftVelocity, kLeftVoltage) =
+      vel_coefs.B_continuous.row(0);
+  B_continuous_model_.block<1, 2>(kRightVelocity, kLeftVoltage) =
+      vel_coefs.B_continuous.row(1);
+
+  B_continuous_accel_(kVelocityX, kAccelX) = 1.0;
+  B_continuous_accel_(kVelocityY, kAccelY) = 1.0;
+  B_continuous_accel_(kTheta, kThetaRate) = 1.0;
+
+  Q_continuous_model_.setZero();
+  Q_continuous_model_.diagonal() << 1e-4, 1e-4, 1e-4, 1e-2, 1e-0, 1e-0, 1e-2,
+      1e-0, 1e-0;
+
+  P_model_ = Q_continuous_model_ * aos::time::DurationInSeconds(kNominalDt);
+}
+
+Eigen::Matrix<double, ModelBasedLocalizer::kNModelStates,
+              ModelBasedLocalizer::kNModelStates>
+ModelBasedLocalizer::AModel(
+    const ModelBasedLocalizer::ModelState &state) const {
+  Eigen::Matrix<double, kNModelStates, kNModelStates> A = A_continuous_model_;
+  const double theta = state(kTheta);
+  const double stheta = std::sin(theta);
+  const double ctheta = std::cos(theta);
+  const double velocity = (state(kLeftVelocity) + state(kRightVelocity)) / 2.0;
+  A(kX, kTheta) = -stheta * velocity;
+  A(kX, kLeftVelocity) = ctheta / 2.0;
+  A(kX, kRightVelocity) = ctheta / 2.0;
+  A(kY, kTheta) = ctheta * velocity;
+  A(kY, kLeftVelocity) = stheta / 2.0;
+  A(kY, kRightVelocity) = stheta / 2.0;
+  return A;
+}
+
+Eigen::Matrix<double, ModelBasedLocalizer::kNAccelStates,
+              ModelBasedLocalizer::kNAccelStates>
+ModelBasedLocalizer::AAccel() const {
+  return A_continuous_accel_;
+}
+
+ModelBasedLocalizer::ModelState ModelBasedLocalizer::DiffModel(
+    const ModelBasedLocalizer::ModelState &state,
+    const ModelBasedLocalizer::ModelInput &U) const {
+  ModelState x_dot = AModel(state) * state + B_continuous_model_ * U;
+  const double theta = state(kTheta);
+  const double stheta = std::sin(theta);
+  const double ctheta = std::cos(theta);
+  const double velocity = (state(kLeftVelocity) + state(kRightVelocity)) / 2.0;
+  x_dot(kX) = ctheta * velocity;
+  x_dot(kY) = stheta * velocity;
+  return x_dot;
+}
+
+ModelBasedLocalizer::AccelState ModelBasedLocalizer::DiffAccel(
+    const ModelBasedLocalizer::AccelState &state,
+    const ModelBasedLocalizer::AccelInput &U) const {
+  return AAccel() * state + B_continuous_accel_ * U;
+}
+
+ModelBasedLocalizer::ModelState ModelBasedLocalizer::UpdateModel(
+    const ModelBasedLocalizer::ModelState &model,
+    const ModelBasedLocalizer::ModelInput &input,
+    const aos::monotonic_clock::duration dt) const {
+  return control_loops::RungeKutta(
+      std::bind(&ModelBasedLocalizer::DiffModel, this, std::placeholders::_1,
+                input),
+      model, aos::time::DurationInSeconds(dt));
+}
+
+ModelBasedLocalizer::AccelState ModelBasedLocalizer::UpdateAccel(
+    const ModelBasedLocalizer::AccelState &accel,
+    const ModelBasedLocalizer::AccelInput &input,
+    const aos::monotonic_clock::duration dt) const {
+  return control_loops::RungeKutta(
+      std::bind(&ModelBasedLocalizer::DiffAccel, this, std::placeholders::_1,
+                input),
+      accel, aos::time::DurationInSeconds(dt));
+}
+
+ModelBasedLocalizer::AccelState ModelBasedLocalizer::AccelStateForModelState(
+    const ModelBasedLocalizer::ModelState &state) const {
+  const double robot_speed =
+      (state(kLeftVelocity) + state(kRightVelocity)) / 2.0;
+  const double velocity_x = std::cos(state(kTheta)) * robot_speed;
+  const double velocity_y = std::sin(state(kTheta)) * robot_speed;
+  return (AccelState() << state(0), state(1), state(2), velocity_x, velocity_y)
+      .finished();
+}
+
+ModelBasedLocalizer::ModelState ModelBasedLocalizer::ModelStateForAccelState(
+    const ModelBasedLocalizer::AccelState &state,
+    const Eigen::Vector2d &encoders, const double yaw_rate) const {
+  const double robot_speed = state(kVelocityX) * std::cos(state(kTheta)) +
+                             state(kVelocityY) * std::sin(state(kTheta));
+  const double radius = dt_config_.robot_radius;
+  const double left_velocity = robot_speed - yaw_rate * radius;
+  const double right_velocity = robot_speed + yaw_rate * radius;
+  return (ModelState() << state(0), state(1), state(2), encoders(0),
+          left_velocity, 0.0, encoders(1), right_velocity, 0.0)
+      .finished();
+}
+
+double ModelBasedLocalizer::ModelDivergence(
+    const ModelBasedLocalizer::CombinedState &state,
+    const ModelBasedLocalizer::AccelInput &accel_inputs,
+    const Eigen::Vector2d &filtered_accel,
+    const ModelBasedLocalizer::ModelInput &model_inputs) {
+  // Convert the model state into the acceleration-based state-space and check
+  // the distance between the two (should really be a weighted norm, but all the
+  // numbers are on ~the same scale).
+  VLOG(2) << "divergence: "
+          << (state.accel_state - AccelStateForModelState(state.model_state))
+                 .transpose();
+  const AccelState diff_accel = DiffAccel(state.accel_state, accel_inputs);
+  const ModelState diff_model = DiffModel(state.model_state, model_inputs);
+  const double model_lng_velocity =
+      (state.model_state(kLeftVelocity) + state.model_state(kRightVelocity)) /
+      2.0;
+  const double model_lng_accel =
+      (diff_model(kLeftVelocity) + diff_model(kRightVelocity)) / 2.0;
+  const Eigen::Vector2d robot_frame_accel(
+      model_lng_accel, diff_model(kTheta) * model_lng_velocity);
+  const Eigen::Vector2d model_accel =
+      Eigen::AngleAxisd(state.model_state(kTheta), Eigen::Vector3d::UnitZ())
+          .toRotationMatrix()
+          .block<2, 2>(0, 0) *
+      robot_frame_accel;
+  const double accel_diff = (model_accel - filtered_accel).norm();
+  const double theta_rate_diff =
+      std::abs(diff_accel(kTheta) - diff_model(kTheta));
+
+  const Eigen::Vector2d accel_vel = state.accel_state.bottomRows<2>();
+  const Eigen::Vector2d model_vel =
+      AccelStateForModelState(state.model_state).bottomRows<2>();
+  velocity_residual_ = (accel_vel - model_vel).norm() /
+                       (1.0 + accel_vel.norm() + model_vel.norm());
+  theta_rate_residual_ = theta_rate_diff;
+  accel_residual_ = accel_diff / 4.0;
+  return velocity_residual_ + theta_rate_residual_ + accel_residual_;
+}
+
+void ModelBasedLocalizer::HandleImu(aos::monotonic_clock::time_point t,
+                                    const Eigen::Vector3d &gyro,
+                                    const Eigen::Vector3d &accel,
+                                    const Eigen::Vector2d encoders,
+                                    const Eigen::Vector2d voltage) {
+  VLOG(2) << t;
+  if (t_ == aos::monotonic_clock::min_time) {
+    t_ = t;
+  }
+  if (t_ + 2 * kNominalDt < t) {
+    t_ = t;
+    ++clock_resets_;
+  }
+  const aos::monotonic_clock::duration dt = t - t_;
+  t_ = t;
+  down_estimator_.Predict(gyro, accel, dt);
+  // TODO(james): Should we prefer this or use the down-estimator corrected
+  // version?
+  const double yaw_rate = (dt_config_.imu_transform * gyro)(2);
+  const double diameter = 2.0 * dt_config_.robot_radius;
+
+  const Eigen::AngleAxis<double> orientation(
+      Eigen::AngleAxis<double>(xytheta()(kTheta), Eigen::Vector3d::UnitZ()) *
+      down_estimator_.X_hat());
+
+  const Eigen::Vector3d absolute_accel =
+      orientation * dt_config_.imu_transform * kG * accel;
+  abs_accel_ = absolute_accel;
+  const Eigen::Vector3d absolute_gyro =
+      orientation * dt_config_.imu_transform * gyro;
+  (void)absolute_gyro;
+
+  VLOG(2) << "abs accel " << absolute_accel.transpose();
+  VLOG(2) << "abs gyro " << absolute_gyro.transpose();
+  VLOG(2) << "dt " << aos::time::DurationInSeconds(dt);
+
+  // Update all the branched states.
+  const AccelInput accel_input(absolute_accel.x(), absolute_accel.y(),
+                               yaw_rate);
+  const ModelInput model_input(voltage);
+
+  const Eigen::Matrix<double, kNModelStates, kNModelStates> A_continuous =
+      AModel(current_state_.model_state);
+
+  Eigen::Matrix<double, kNModelStates, kNModelStates> A_discrete;
+  Eigen::Matrix<double, kNModelStates, kNModelStates> Q_discrete;
+
+  DiscretizeQAFast(Q_continuous_model_, A_continuous, dt, &Q_discrete,
+                   &A_discrete);
+
+  P_model_ = A_discrete * P_model_ * A_discrete.transpose() + Q_discrete;
+
+  Eigen::Matrix<double, kNModelOutputs, kNModelStates> H;
+  Eigen::Matrix<double, kNModelOutputs, kNModelOutputs> R;
+  {
+    H.setZero();
+    R.setZero();
+    H(0, kLeftEncoder) = 1.0;
+    H(1, kRightEncoder) = 1.0;
+    H(2, kRightVelocity) = 1.0 / diameter;
+    H(2, kLeftVelocity) = -1.0 / diameter;
+
+    R.diagonal() << 1e-9, 1e-9, 1e-13;
+  }
+
+  const Eigen::Matrix<double, kNModelOutputs, 1> Z(encoders(0), encoders(1),
+                                                   yaw_rate);
+
+  if (branches_.empty()) {
+    VLOG(2) << "Initializing";
+    current_state_.model_state.setZero();
+    current_state_.accel_state.setZero();
+    current_state_.model_state(kLeftEncoder) = encoders(0);
+    current_state_.model_state(kRightEncoder) = encoders(1);
+    current_state_.branch_time = t;
+    branches_.Push(current_state_);
+  }
+
+  const Eigen::Matrix<double, kNModelStates, kNModelOutputs> K =
+      P_model_ * H.transpose() * (H * P_model_ * H.transpose() + R).inverse();
+  P_model_ = (Eigen::Matrix<double, kNModelStates, kNModelStates>::Identity() -
+              K * H) *
+             P_model_;
+  VLOG(2) << "K\n" << K;
+  VLOG(2) << "Z\n" << Z.transpose();
+
+  for (CombinedState &state : branches_) {
+    state.accel_state = UpdateAccel(state.accel_state, accel_input, dt);
+    if (down_estimator_.consecutive_still() > 100.0) {
+      state.accel_state(kVelocityX) *= 0.9;
+      state.accel_state(kVelocityY) *= 0.9;
+    }
+    state.model_state = UpdateModel(state.model_state, model_input, dt);
+    state.model_state += K * (Z - H * state.model_state);
+  }
+
+  VLOG(2) << "oildest accel " << branches_[0].accel_state.transpose();
+  VLOG(2) << "oildest accel diff "
+          << DiffAccel(branches_[0].accel_state, accel_input).transpose();
+  VLOG(2) << "oildest model " << branches_[0].model_state.transpose();
+
+  // Determine whether to switch modes--if we are currently in model-based mode,
+  // swap to accel-based if the two states have divergeed meaningfully in the
+  // oldest branch. If we are currently in accel-based, then swap back to model
+  // if the oldest model branch matches has matched the
+  filtered_residual_accel_ +=
+      0.01 * (accel_input.topRows<2>() - filtered_residual_accel_);
+  const double model_divergence =
+      branches_.full() ? ModelDivergence(branches_[0], accel_input,
+                                         filtered_residual_accel_, model_input)
+                       : 0.0;
+  filtered_residual_ +=
+      (1.0 - std::exp(-aos::time::DurationInSeconds(kNominalDt) / 0.0095)) *
+      (model_divergence - filtered_residual_);
+  constexpr double kUseAccelThreshold = 0.4;
+  constexpr double kUseModelThreshold = 0.2;
+  constexpr size_t kShareStates = kNModelStates;
+  static_assert(kUseModelThreshold < kUseAccelThreshold);
+  if (using_model_) {
+    if (filtered_residual_ > kUseAccelThreshold) {
+      hysteresis_count_++;
+    } else {
+      hysteresis_count_ = 0;
+    }
+    if (hysteresis_count_ > 0) {
+      using_model_ = false;
+      // Grab the accel-based state from back when we started diverging.
+      // TODO(james): This creates a problematic selection bias, because
+      // we will tend to bias towards deliberately out-of-tune measurements.
+      current_state_.accel_state = branches_[0].accel_state;
+      current_state_.model_state = branches_[0].model_state;
+      current_state_.model_state = ModelStateForAccelState(
+          current_state_.accel_state, encoders, yaw_rate);
+    } else {
+      VLOG(2) << "Normal branching";
+      current_state_.model_state = branches_[branches_.size() - 1].model_state;
+      current_state_.accel_state =
+          AccelStateForModelState(current_state_.model_state);
+      current_state_.branch_time = t;
+    }
+    hysteresis_count_ = 0;
+  } else {
+    if (filtered_residual_ < kUseModelThreshold) {
+      hysteresis_count_++;
+    } else {
+      hysteresis_count_ = 0;
+    }
+    if (hysteresis_count_ > 100) {
+      using_model_ = true;
+      // Grab the model-based state from back when we stopped diverging.
+      current_state_.model_state.topRows<kShareStates>() =
+          ModelStateForAccelState(branches_[0].accel_state, encoders, yaw_rate)
+              .topRows<kShareStates>();
+      current_state_.accel_state =
+          AccelStateForModelState(current_state_.model_state);
+    } else {
+      current_state_.accel_state = branches_[branches_.size() - 1].accel_state;
+      // TODO(james): Why was I leaving the encoders/wheel velocities in place?
+      current_state_.model_state = branches_[branches_.size() - 1].model_state;
+      current_state_.model_state = ModelStateForAccelState(
+          current_state_.accel_state, encoders, yaw_rate);
+      current_state_.branch_time = t;
+    }
+  }
+
+  // Generate a new branch, with the accel state reset based on the model-based
+  // state (really, just getting rid of the lateral velocity).
+  CombinedState new_branch = current_state_;
+  //if (!keep_accel_state) {
+  if (using_model_) {
+    new_branch.accel_state = AccelStateForModelState(new_branch.model_state);
+  }
+  new_branch.accumulated_divergence = 0.0;
+
+  ++branch_counter_;
+  if (branch_counter_ % kBranchPeriod == 0) {
+    branches_.Push(new_branch);
+    branch_counter_ = 0;
+  }
+
+  last_residual_ = model_divergence;
+
+  VLOG(2) << "Using " << (using_model_ ? "model" : "accel");
+  VLOG(2) << "Residual " << last_residual_;
+  VLOG(2) << "Filtered Residual " << filtered_residual_;
+  VLOG(2) << "buffer size " << branches_.size();
+  VLOG(2) << "Model state " << current_state_.model_state.transpose();
+  VLOG(2) << "Accel state " << current_state_.accel_state.transpose();
+  VLOG(2) << "Accel state for model "
+            << AccelStateForModelState(current_state_.model_state).transpose();
+  VLOG(2) << "Input acce " << accel.transpose();
+  VLOG(2) << "Input gyro " << gyro.transpose();
+  VLOG(2) << "Input voltage " << voltage.transpose();
+  VLOG(2) << "Input encoder " << encoders.transpose();
+  VLOG(2) << "yaw rate " << yaw_rate;
+
+  CHECK(std::isfinite(last_residual_));
+}
+
+void ModelBasedLocalizer::HandleReset(aos::monotonic_clock::time_point now,
+                                      const Eigen::Vector3d &xytheta) {
+  branches_.Reset();
+  t_ =  now;
+  using_model_ = true;
+  current_state_.model_state << xytheta(0), xytheta(1), xytheta(2),
+      current_state_.model_state(kLeftEncoder), 0.0, 0.0,
+      current_state_.model_state(kRightEncoder), 0.0, 0.0;
+  current_state_.accel_state =
+      AccelStateForModelState(current_state_.model_state);
+  last_residual_ = 0.0;
+  filtered_residual_ = 0.0;
+  filtered_residual_accel_.setZero();
+  abs_accel_.setZero();
+}
+
+flatbuffers::Offset<AccelBasedState> ModelBasedLocalizer::BuildAccelState(
+    flatbuffers::FlatBufferBuilder *fbb, const AccelState &state) {
+  AccelBasedState::Builder accel_state_builder(*fbb);
+  accel_state_builder.add_x(state(kX));
+  accel_state_builder.add_y(state(kY));
+  accel_state_builder.add_theta(state(kTheta));
+  accel_state_builder.add_velocity_x(state(kVelocityX));
+  accel_state_builder.add_velocity_y(state(kVelocityY));
+  return accel_state_builder.Finish();
+}
+
+flatbuffers::Offset<ModelBasedState> ModelBasedLocalizer::BuildModelState(
+    flatbuffers::FlatBufferBuilder *fbb, const ModelState &state) {
+  ModelBasedState::Builder model_state_builder(*fbb);
+  model_state_builder.add_x(state(kX));
+  model_state_builder.add_y(state(kY));
+  model_state_builder.add_theta(state(kTheta));
+  model_state_builder.add_left_encoder(state(kLeftEncoder));
+  model_state_builder.add_left_velocity(state(kLeftVelocity));
+  model_state_builder.add_left_voltage_error(state(kLeftVoltageError));
+  model_state_builder.add_right_encoder(state(kRightEncoder));
+  model_state_builder.add_right_velocity(state(kRightVelocity));
+  model_state_builder.add_right_voltage_error(state(kRightVoltageError));
+  return model_state_builder.Finish();
+}
+
+flatbuffers::Offset<ModelBasedStatus> ModelBasedLocalizer::PopulateStatus(
+    flatbuffers::FlatBufferBuilder *fbb) {
+  const flatbuffers::Offset<control_loops::drivetrain::DownEstimatorState>
+      down_estimator_offset = down_estimator_.PopulateStatus(fbb, t_);
+
+  const CombinedState &state = current_state_;
+
+  const flatbuffers::Offset<ModelBasedState> model_state_offset =
+    BuildModelState(fbb, state.model_state);
+
+  const flatbuffers::Offset<AccelBasedState> accel_state_offset =
+      BuildAccelState(fbb, state.accel_state);
+
+  const flatbuffers::Offset<AccelBasedState> oldest_accel_state_offset =
+      branches_.empty() ? flatbuffers::Offset<AccelBasedState>()
+                        : BuildAccelState(fbb, branches_[0].accel_state);
+
+  const flatbuffers::Offset<ModelBasedState> oldest_model_state_offset =
+      branches_.empty() ? flatbuffers::Offset<ModelBasedState>()
+                        : BuildModelState(fbb, branches_[0].model_state);
+
+  ModelBasedStatus::Builder builder(*fbb);
+  builder.add_accel_state(accel_state_offset);
+  builder.add_oldest_accel_state(oldest_accel_state_offset);
+  builder.add_oldest_model_state(oldest_model_state_offset);
+  builder.add_model_state(model_state_offset);
+  builder.add_using_model(using_model_);
+  builder.add_residual(last_residual_);
+  builder.add_filtered_residual(filtered_residual_);
+  builder.add_velocity_residual(velocity_residual_);
+  builder.add_accel_residual(accel_residual_);
+  builder.add_theta_rate_residual(theta_rate_residual_);
+  builder.add_down_estimator(down_estimator_offset);
+  builder.add_x(xytheta()(0));
+  builder.add_y(xytheta()(1));
+  builder.add_theta(xytheta()(2));
+  builder.add_implied_accel_x(abs_accel_(0));
+  builder.add_implied_accel_y(abs_accel_(1));
+  builder.add_implied_accel_z(abs_accel_(2));
+  builder.add_clock_resets(clock_resets_);
+  return builder.Finish();
+}
+
+EventLoopLocalizer::EventLoopLocalizer(
+    aos::EventLoop *event_loop,
+    const control_loops::drivetrain::DrivetrainConfig<double> &dt_config)
+    : event_loop_(event_loop),
+      model_based_(dt_config),
+      status_sender_(event_loop_->MakeSender<LocalizerStatus>("/localizer")),
+      output_sender_(event_loop_->MakeSender<LocalizerOutput>("/localizer")),
+      output_fetcher_(
+          event_loop_->MakeFetcher<frc971::control_loops::drivetrain::Output>(
+              "/drivetrain")) {
+  event_loop_->MakeWatcher(
+      "/drivetrain",
+      [this](
+          const frc971::control_loops::drivetrain::LocalizerControl &control) {
+        const double theta = control.keep_current_theta()
+                                 ? model_based_.xytheta()(2)
+                                 : control.theta();
+        model_based_.HandleReset(event_loop_->monotonic_now(),
+                               {control.x(), control.y(), theta});
+      });
+  event_loop_->MakeWatcher(
+      "/localizer", [this](const frc971::IMUValuesBatch &values) {
+        CHECK(values.has_readings());
+        output_fetcher_.Fetch();
+        for (const IMUValues *value : *values.readings()) {
+          zeroer_.InsertAndProcessMeasurement(*value);
+          if (zeroer_.Zeroed()) {
+            if (output_fetcher_.get() != nullptr) {
+              const bool disabled =
+                  output_fetcher_.context().monotonic_event_time +
+                      std::chrono::milliseconds(10) <
+                  event_loop_->context().monotonic_event_time;
+              model_based_.HandleImu(
+                  aos::monotonic_clock::time_point(std::chrono::nanoseconds(
+                      value->monotonic_timestamp_ns())),
+                  zeroer_.ZeroedGyro(), zeroer_.ZeroedAccel(),
+                  {value->left_encoder(), value->right_encoder()},
+                  disabled ? Eigen::Vector2d::Zero()
+                           : Eigen::Vector2d{output_fetcher_->left_voltage(),
+                                             output_fetcher_->right_voltage()});
+            }
+          }
+          {
+            auto builder = status_sender_.MakeBuilder();
+            const flatbuffers::Offset<ModelBasedStatus> model_based_status =
+                model_based_.PopulateStatus(builder.fbb());
+            LocalizerStatus::Builder status_builder =
+                builder.MakeBuilder<LocalizerStatus>();
+            status_builder.add_model_based(model_based_status);
+            status_builder.add_zeroed(zeroer_.Zeroed());
+            status_builder.add_faulted_zero(zeroer_.Faulted());
+            builder.CheckOk(builder.Send(status_builder.Finish()));
+          }
+          if (last_output_send_ + std::chrono::milliseconds(5) <
+              event_loop_->context().monotonic_event_time) {
+            auto builder = output_sender_.MakeBuilder();
+            LocalizerOutput::Builder output_builder =
+                builder.MakeBuilder<LocalizerOutput>();
+            // TODO(james): Should we bother to try to estimate time offsets for
+            // the pico?
+            output_builder.add_monotonic_timestamp_ns(
+                value->monotonic_timestamp_ns());
+            output_builder.add_x(model_based_.xytheta()(0));
+            output_builder.add_y(model_based_.xytheta()(1));
+            output_builder.add_theta(model_based_.xytheta()(2));
+            builder.CheckOk(builder.Send(output_builder.Finish()));
+            last_output_send_ = event_loop_->monotonic_now();
+          }
+        }
+      });
+}
+
+}  // namespace frc971::controls
diff --git a/y2022/control_loops/localizer/localizer.h b/y2022/control_loops/localizer/localizer.h
new file mode 100644
index 0000000..bb52a40
--- /dev/null
+++ b/y2022/control_loops/localizer/localizer.h
@@ -0,0 +1,220 @@
+#ifndef Y2022_CONTROL_LOOPS_LOCALIZER_LOCALIZER_H_
+#define Y2022_CONTROL_LOOPS_LOCALIZER_LOCALIZER_H_
+
+#include "Eigen/Dense"
+#include "Eigen/Geometry"
+
+#include "aos/events/event_loop.h"
+#include "aos/containers/ring_buffer.h"
+#include "aos/time/time.h"
+#include "y2020/vision/sift/sift_generated.h"
+#include "y2022/control_loops/localizer/localizer_status_generated.h"
+#include "y2022/control_loops/localizer/localizer_output_generated.h"
+#include "frc971/control_loops/drivetrain/improved_down_estimator.h"
+#include "frc971/control_loops/drivetrain/drivetrain_output_generated.h"
+#include "frc971/control_loops/drivetrain/localizer_generated.h"
+#include "frc971/zeroing/imu_zeroer.h"
+
+namespace frc971::controls {
+
+namespace testing {
+class LocalizerTest;
+}
+
+// Localizer implementation that makes use of a 6-axis IMU, encoder readings,
+// drivetrain voltages, and camera returns to localize the robot. Meant to
+// be run on a raspberry pi.
+//
+// This operates on the principle that the drivetrain can be in one of two
+// modes:
+// 1) A "normal" mode where it is obeying the regular drivetrain model, with
+//    minimal lateral motion and no major external disturbances. This is
+//    referred to as the "model" mode in the code/variable names.
+// 2) An non-holonomic mode where the robot is just flying around on a 2-D
+//    plane with no meaningful constraints (referred to as an "accel" model
+//    in the code, because we rely primarily on the accelerometer readings).
+//
+// In order to determine which mode to be in, we attempt to track whether the
+// two models are diverging substantially. In order to do this, we maintain a
+// 1-second long queue of "branches". A branch is generated every X iterations
+// and contains a model state and an accel state. When the branch starts, the
+// two will have identical states. For the remaining 1 second, the model state
+// will evolve purely according to the drivetrian model, and the accel state
+// will evolve purely using IMU readings.
+//
+// When the branch reaches 1 second in age, we calculate a residual associated
+// with how much the accel and model based states diverged. If they have
+// diverged substantially, that implies that the model is a poor match for
+// whatever has been happening to the robot in the past second, so if we were
+// previously relying on the model, we will override the current "actual"
+// state with the branched accel state, and then continue to update the accel
+// state based on IMU readings.
+// If we are currently in the accel state, we will continue generating branches
+// until the branches stop diverging--this will indicate that the model
+// matches the accelerometer readings again, and so we will swap back to
+// the model-based state.
+//
+// TODO:
+// * Implement paying attention to camera readings.
+// * Tune for ADIS16505/real robot.
+// * Tune down CPU usage to run on a pi.
+class ModelBasedLocalizer {
+ public:
+  static constexpr size_t kX = 0;
+  static constexpr size_t kY = 1;
+  static constexpr size_t kTheta = 2;
+
+  static constexpr size_t kVelocityX = 3;
+  static constexpr size_t kVelocityY = 4;
+  static constexpr size_t kNAccelStates = 5;
+
+  static constexpr size_t kLeftEncoder = 3;
+  static constexpr size_t kLeftVelocity = 4;
+  static constexpr size_t kLeftVoltageError = 5;
+  static constexpr size_t kRightEncoder = 6;
+  static constexpr size_t kRightVelocity = 7;
+  static constexpr size_t kRightVoltageError = 8;
+  static constexpr size_t kNModelStates = 9;
+
+  static constexpr size_t kNModelOutputs = 3;
+
+  static constexpr size_t kNAccelOuputs = 1;
+
+  static constexpr size_t kAccelX = 0;
+  static constexpr size_t kAccelY = 1;
+  static constexpr size_t kThetaRate = 2;
+  static constexpr size_t kNAccelInputs = 3;
+
+  static constexpr size_t kLeftVoltage = 0;
+  static constexpr size_t kRightVoltage = 1;
+  static constexpr size_t kNModelInputs = 2;
+
+  // Branching period, in cycles.
+  static constexpr int kBranchPeriod = 1;
+
+  typedef Eigen::Matrix<double, kNModelStates, 1> ModelState;
+  typedef Eigen::Matrix<double, kNAccelStates, 1> AccelState;
+  typedef Eigen::Matrix<double, kNModelInputs, 1> ModelInput;
+  typedef Eigen::Matrix<double, kNAccelInputs, 1> AccelInput;
+
+  ModelBasedLocalizer(
+      const control_loops::drivetrain::DrivetrainConfig<double> &dt_config);
+  void HandleImu(aos::monotonic_clock::time_point t,
+                 const Eigen::Vector3d &gyro, const Eigen::Vector3d &accel,
+                 const Eigen::Vector2d encoders, const Eigen::Vector2d voltage);
+  void HandleImageMatch(aos::monotonic_clock::time_point,
+                        const vision::sift::ImageMatchResult *) {
+    LOG(FATAL) << "Unimplemented.";
+  }
+  void HandleReset(aos::monotonic_clock::time_point,
+                   const Eigen::Vector3d &xytheta);
+
+  flatbuffers::Offset<ModelBasedStatus> PopulateStatus(
+      flatbuffers::FlatBufferBuilder *fbb);
+
+  Eigen::Vector3d xytheta() const {
+    if (using_model_) {
+      return current_state_.model_state.block<3, 1>(0, 0);
+    } else {
+      return current_state_.accel_state.block<3, 1>(0, 0);
+    }
+  }
+
+  AccelState accel_state() const { return current_state_.accel_state; };
+
+ private:
+  struct CombinedState {
+    AccelState accel_state;
+    ModelState model_state;
+    aos::monotonic_clock::time_point branch_time;
+    double accumulated_divergence;
+  };
+
+  static flatbuffers::Offset<AccelBasedState> BuildAccelState(
+      flatbuffers::FlatBufferBuilder *fbb, const AccelState &state);
+
+  static flatbuffers::Offset<ModelBasedState> BuildModelState(
+      flatbuffers::FlatBufferBuilder *fbb, const ModelState &state);
+
+  Eigen::Matrix<double, kNModelStates, kNModelStates> AModel(
+      const ModelState &state) const;
+  Eigen::Matrix<double, kNAccelStates, kNAccelStates> AAccel() const;
+  ModelState DiffModel(const ModelState &state, const ModelInput &U) const;
+  AccelState DiffAccel(const AccelState &state, const AccelInput &U) const;
+
+  ModelState UpdateModel(const ModelState &model, const ModelInput &input,
+                         aos::monotonic_clock::duration dt) const;
+  AccelState UpdateAccel(const AccelState &accel, const AccelInput &input,
+                         aos::monotonic_clock::duration dt) const;
+
+  AccelState AccelStateForModelState(const ModelState &state) const;
+  ModelState ModelStateForAccelState(const AccelState &state,
+                                     const Eigen::Vector2d &encoders,
+                                     const double yaw_rate) const;
+  double ModelDivergence(const CombinedState &state,
+                         const AccelInput &accel_inputs,
+                         const Eigen::Vector2d &filtered_accel,
+                         const ModelInput &model_inputs);
+
+  const control_loops::drivetrain::DrivetrainConfig<double> dt_config_;
+  const StateFeedbackHybridPlantCoefficients<2, 2, 2, double>
+      velocity_drivetrain_coefficients_;
+  Eigen::Matrix<double, kNModelStates, kNModelStates> A_continuous_model_;
+  Eigen::Matrix<double, kNAccelStates, kNAccelStates> A_continuous_accel_;
+  Eigen::Matrix<double, kNModelStates, kNModelInputs> B_continuous_model_;
+  Eigen::Matrix<double, kNAccelStates, kNAccelInputs> B_continuous_accel_;
+
+  Eigen::Matrix<double, kNModelStates, kNModelStates> Q_continuous_model_;
+
+  Eigen::Matrix<double, kNModelStates, kNModelStates> P_model_;
+  // When we are following the model, we will, on each iteration:
+  // 1) Perform a model-based update of a single state.
+  // 2) Add a hypothetical non-model-based entry based on the current state.
+  // 3) Evict too-old non-model-based entries.
+  control_loops::drivetrain::DrivetrainUkf down_estimator_;
+
+  // Buffer of old branches these are all created by initializing a new
+  // model-based state based on the current state, and then initializing a new
+  // accel-based state on top of that new model-based state (to eliminate the
+  // impact of any lateral motion).
+  // We then integrate up all of these states and observe how much the model and
+  // accel based states of each branch compare to one another.
+  aos::RingBuffer<CombinedState, 2000 / kBranchPeriod> branches_;
+  int branch_counter_ = 0;
+
+  CombinedState current_state_;
+  aos::monotonic_clock::time_point t_ = aos::monotonic_clock::min_time;
+  bool using_model_;
+
+  double last_residual_ = 0.0;
+  double filtered_residual_ = 0.0;
+  Eigen::Vector2d filtered_residual_accel_ = Eigen::Vector2d::Zero();
+  Eigen::Vector3d abs_accel_ = Eigen::Vector3d::Zero();
+  double velocity_residual_ = 0.0;
+  double accel_residual_ = 0.0;
+  double theta_rate_residual_ = 0.0;
+  int hysteresis_count_ = 0;
+
+  int clock_resets_ = 0;
+
+  friend class testing::LocalizerTest;
+};
+
+class EventLoopLocalizer {
+ public:
+  EventLoopLocalizer(
+      aos::EventLoop *event_loop,
+      const control_loops::drivetrain::DrivetrainConfig<double> &dt_config);
+
+ private:
+  aos::EventLoop *event_loop_;
+  ModelBasedLocalizer model_based_;
+  aos::Sender<LocalizerStatus> status_sender_;
+  aos::Sender<LocalizerOutput> output_sender_;
+  aos::Fetcher<frc971::control_loops::drivetrain::Output> output_fetcher_;
+  zeroing::ImuZeroer zeroer_;
+  aos::monotonic_clock::time_point last_output_send_ =
+      aos::monotonic_clock::min_time;
+};
+}  // namespace frc971::controls
+#endif // Y2022_CONTROL_LOOPS_LOCALIZER_LOCALIZER_H_
diff --git a/y2022/control_loops/localizer/localizer_main.cc b/y2022/control_loops/localizer/localizer_main.cc
new file mode 100644
index 0000000..0cc53bb
--- /dev/null
+++ b/y2022/control_loops/localizer/localizer_main.cc
@@ -0,0 +1,21 @@
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "y2022/control_loops/localizer/localizer.h"
+#include "y2022/control_loops/drivetrain/drivetrain_base.h"
+
+DEFINE_string(config, "config.json", "Path to the config file to use.");
+
+int main(int argc, char *argv[]) {
+  aos::InitGoogle(&argc, &argv);
+
+  aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+      aos::configuration::ReadConfig(FLAGS_config);
+
+  aos::ShmEventLoop event_loop(&config.message());
+  frc971::controls::EventLoopLocalizer localizer(
+      &event_loop, ::y2022::control_loops::drivetrain::GetDrivetrainConfig());
+
+  event_loop.Run();
+
+  return 0;
+}
diff --git a/y2022/control_loops/localizer/localizer_output.fbs b/y2022/control_loops/localizer/localizer_output.fbs
new file mode 100644
index 0000000..078d723
--- /dev/null
+++ b/y2022/control_loops/localizer/localizer_output.fbs
@@ -0,0 +1,17 @@
+namespace frc971.controls;
+
+// This provides a minimal output from the localizer that can be forwarded to
+// the roborio and used for corrections to its (simpler) localizer.
+
+table LocalizerOutput {
+  // Timestamp (on the source node) that this sample corresponds with. This
+  // may be older than the sent time to account for delays in sensor readings.
+  monotonic_timestamp_ns:int64 (id: 0);
+  // Current x/y position estimate, in meters.
+  x:double (id: 1);
+  y:double (id: 2);
+  // Current heading, in radians.
+  theta:double (id: 3);
+}
+
+root_type LocalizerOutput;
diff --git a/y2022/control_loops/localizer/localizer_plotter.ts b/y2022/control_loops/localizer/localizer_plotter.ts
new file mode 100644
index 0000000..ce348e7
--- /dev/null
+++ b/y2022/control_loops/localizer/localizer_plotter.ts
@@ -0,0 +1,267 @@
+// Provides a plot for debugging drivetrain-related issues.
+import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
+import {ImuMessageHandler} from 'org_frc971/frc971/wpilib/imu_plot_utils';
+import * as proxy from 'org_frc971/aos/network/www/proxy';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from 'org_frc971/aos/network/www/colors';
+
+import Connection = proxy.Connection;
+
+const TIME = AosPlotter.TIME;
+const DEFAULT_WIDTH = AosPlotter.DEFAULT_WIDTH;
+const DEFAULT_HEIGHT = AosPlotter.DEFAULT_HEIGHT;
+
+export function plotLocalizer(conn: Connection, element: Element): void {
+  const aosPlotter = new AosPlotter(conn);
+
+  const position = aosPlotter.addMessageSource("/drivetrain",
+      "frc971.control_loops.drivetrain.Position");
+  const status = aosPlotter.addMessageSource(
+      '/drivetrain', 'frc971.control_loops.drivetrain.Status');
+  const output = aosPlotter.addMessageSource(
+      '/drivetrain', 'frc971.control_loops.drivetrain.Output');
+  const localizer = aosPlotter.addMessageSource(
+      '/localizer', 'frc971.controls.LocalizerStatus');
+  const imu = aosPlotter.addRawMessageSource(
+      '/drivetrain', 'frc971.IMUValuesBatch',
+      new ImuMessageHandler(conn.getSchema('frc971.IMUValuesBatch')));
+
+  // Drivetrain Status estimated relative position
+  const positionPlot = aosPlotter.addPlot(element);
+  positionPlot.plot.getAxisLabels().setTitle("Estimated Relative Position " +
+                                             "of the Drivetrain");
+  positionPlot.plot.getAxisLabels().setXLabel(TIME);
+  positionPlot.plot.getAxisLabels().setYLabel("Relative Position (m)");
+  const leftPosition =
+      positionPlot.addMessageLine(status, ["estimated_left_position"]);
+  leftPosition.setColor(RED);
+  const rightPosition =
+      positionPlot.addMessageLine(status, ["estimated_right_position"]);
+  rightPosition.setColor(GREEN);
+  positionPlot
+      .addMessageLine(localizer, ['model_based', 'model_state', 'left_encoder'])
+      .setColor(BROWN)
+      .setPointSize(0.0);
+  positionPlot
+      .addMessageLine(localizer, ['model_based', 'model_state', 'right_encoder'])
+      .setColor(CYAN)
+      .setPointSize(0.0);
+  positionPlot.addMessageLine(position, ['left_encoder'])
+      .setColor(BROWN)
+      .setDrawLine(false);
+  positionPlot.addMessageLine(position, ['right_encoder'])
+      .setColor(CYAN)
+      .setDrawLine(false);
+
+
+  // Drivetrain Velocities
+  const velocityPlot = aosPlotter.addPlot(element);
+  velocityPlot.plot.getAxisLabels().setTitle('Velocity Plots');
+  velocityPlot.plot.getAxisLabels().setXLabel(TIME);
+  velocityPlot.plot.getAxisLabels().setYLabel('Wheel Velocity (m/s)');
+
+  const leftVelocity =
+      velocityPlot.addMessageLine(status, ['estimated_left_velocity']);
+  leftVelocity.setColor(RED);
+  const rightVelocity =
+      velocityPlot.addMessageLine(status, ['estimated_right_velocity']);
+  rightVelocity.setColor(GREEN);
+
+  const leftSpeed = velocityPlot.addMessageLine(position, ["left_speed"]);
+  leftSpeed.setColor(BLUE);
+  const rightSpeed = velocityPlot.addMessageLine(position, ["right_speed"]);
+  rightSpeed.setColor(BROWN);
+
+  const ekfLeftVelocity = velocityPlot.addMessageLine(
+      localizer, ['model_based', 'model_state', 'left_velocity']);
+  ekfLeftVelocity.setColor(RED);
+  ekfLeftVelocity.setPointSize(0.0);
+  const ekfRightVelocity = velocityPlot.addMessageLine(
+      localizer, ['model_based', 'model_state', 'right_velocity']);
+  ekfRightVelocity.setColor(GREEN);
+  ekfRightVelocity.setPointSize(0.0);
+
+  velocityPlot
+      .addMessageLine(
+          localizer, ['model_based', 'oldest_model_state', 'left_velocity'])
+      .setColor(RED)
+      .setDrawLine(false);
+
+  velocityPlot
+      .addMessageLine(
+          localizer, ['model_based', 'oldest_model_state', 'right_velocity'])
+      .setColor(GREEN)
+      .setDrawLine(false);
+
+  const splineVelocityOffset =
+      velocityPlot
+          .addMessageLine(status, ['localizer', 'longitudinal_velocity_offset'])
+          .setColor(BROWN)
+          .setPointSize(0.0);
+
+  const splineLateralVelocity =
+      velocityPlot.addMessageLine(status, ['localizer', 'lateral_velocity'])
+          .setColor(PINK)
+          .setPointSize(0.0);
+
+  // Drivetrain Voltage
+  const voltagePlot = aosPlotter.addPlot(element);
+  voltagePlot.plot.getAxisLabels().setTitle('Voltage Plots');
+  voltagePlot.plot.getAxisLabels().setXLabel(TIME);
+  voltagePlot.plot.getAxisLabels().setYLabel('Voltage (V)')
+
+  voltagePlot.addMessageLine(localizer, ['model_based', 'model_state', 'left_voltage_error'])
+      .setColor(RED)
+      .setDrawLine(false);
+  voltagePlot.addMessageLine(localizer, ['model_based', 'model_state', 'right_voltage_error'])
+      .setColor(GREEN)
+      .setDrawLine(false);
+  voltagePlot.addMessageLine(output, ['left_voltage'])
+      .setColor(RED)
+      .setPointSize(0);
+  voltagePlot.addMessageLine(output, ['right_voltage'])
+      .setColor(GREEN)
+      .setPointSize(0);
+
+  // Heading
+  const yawPlot = aosPlotter.addPlot(element);
+  yawPlot.plot.getAxisLabels().setTitle('Robot Yaw');
+  yawPlot.plot.getAxisLabels().setXLabel(TIME);
+  yawPlot.plot.getAxisLabels().setYLabel('Yaw (rad)');
+
+  yawPlot.addMessageLine(status, ['localizer', 'theta']).setColor(GREEN);
+
+  yawPlot.addMessageLine(status, ['down_estimator', 'yaw']).setColor(BLUE);
+
+  yawPlot.addMessageLine(localizer, ['model_based', 'theta']).setColor(RED);
+
+  // Pitch/Roll
+  const orientationPlot = aosPlotter.addPlot(element);
+  orientationPlot.plot.getAxisLabels().setTitle('Orientation');
+  orientationPlot.plot.getAxisLabels().setXLabel(TIME);
+  orientationPlot.plot.getAxisLabels().setYLabel('Angle (rad)');
+
+  orientationPlot.addMessageLine(localizer, ['model_based', 'down_estimator', 'lateral_pitch'])
+      .setColor(RED)
+      .setLabel('roll');
+  orientationPlot
+      .addMessageLine(localizer, ['model_based', 'down_estimator', 'longitudinal_pitch'])
+      .setColor(GREEN)
+      .setLabel('pitch');
+
+  const stillPlot = aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 3]);
+  stillPlot.plot.getAxisLabels().setTitle('Still Plot');
+  stillPlot.plot.getAxisLabels().setXLabel(TIME);
+  stillPlot.plot.getAxisLabels().setYLabel('bool, g\'s');
+  stillPlot.plot.setDefaultYRange([-0.1, 1.1]);
+
+  stillPlot.addMessageLine(localizer, ['model_based', 'down_estimator', 'gravity_magnitude'])
+      .setColor(WHITE)
+      .setDrawLine(false);
+  stillPlot.addMessageLine(localizer, ['model_based', 'using_model'])
+      .setColor(PINK)
+      .setDrawLine(false);
+
+  // Accelerometer/Gravity
+  const accelPlot = aosPlotter.addPlot(element);
+  accelPlot.plot.getAxisLabels().setTitle('Absoluate Velocities')
+  accelPlot.plot.getAxisLabels().setYLabel('Velocity (m/s)');
+  accelPlot.plot.getAxisLabels().setXLabel('Monotonic Time (sec)');
+
+  accelPlot.addMessageLine(localizer, ['no_wheel_status', 'velocity_x'])
+      .setColor(PINK);
+  accelPlot.addMessageLine(localizer, ['no_wheel_status', 'velocity_y'])
+      .setColor(GREEN);
+  accelPlot.addMessageLine(localizer, ['no_wheel_status', 'velocity_z'])
+      .setColor(BLUE);
+
+  accelPlot.addMessageLine(localizer, ['model_based', 'accel_state', 'velocity_x'])
+      .setColor(RED)
+      .setDrawLine(false);
+  accelPlot.addMessageLine(localizer, ['model_based', 'accel_state', 'velocity_y'])
+      .setColor(GREEN)
+      .setDrawLine(false);
+
+  accelPlot.addMessageLine(localizer, ['model_based', 'oldest_accel_state', 'velocity_x'])
+      .setColor(RED)
+      .setPointSize(0);
+  accelPlot.addMessageLine(localizer, ['model_based', 'oldest_accel_state', 'velocity_y'])
+      .setColor(GREEN)
+      .setPointSize(0);
+
+  // Absolute X Position
+  const xPositionPlot = aosPlotter.addPlot(element);
+  xPositionPlot.plot.getAxisLabels().setTitle('X Position');
+  xPositionPlot.plot.getAxisLabels().setXLabel(TIME);
+  xPositionPlot.plot.getAxisLabels().setYLabel('X Position (m)');
+
+  xPositionPlot.addMessageLine(status, ['x']).setColor(RED);
+  xPositionPlot.addMessageLine(status, ['down_estimator', 'position_x'])
+      .setColor(BLUE);
+  xPositionPlot.addMessageLine(localizer, ['no_wheel_status', 'x']).setColor(GREEN);
+  xPositionPlot.addMessageLine(localizer, ['model_based', 'x']).setColor(CYAN);
+
+  xPositionPlot.plot.setDefaultYRange([0.0, 0.5]);
+
+  // Absolute Y Position
+  const yPositionPlot = aosPlotter.addPlot(element);
+  yPositionPlot.plot.getAxisLabels().setTitle('Y Position');
+  yPositionPlot.plot.getAxisLabels().setXLabel(TIME);
+  yPositionPlot.plot.getAxisLabels().setYLabel('Y Position (m)');
+
+  const localizerY = yPositionPlot.addMessageLine(status, ['y']);
+  localizerY.setColor(RED);
+  yPositionPlot.addMessageLine(status, ['down_estimator', 'position_y'])
+      .setColor(BLUE);
+  yPositionPlot.addMessageLine(localizer, ['no_wheel_status', 'y']).setColor(GREEN);
+  yPositionPlot.addMessageLine(localizer, ['model_based', 'y']).setColor(CYAN);
+
+  // Gyro
+  const gyroPlot = aosPlotter.addPlot(element);
+  gyroPlot.plot.getAxisLabels().setTitle('Gyro Readings');
+  gyroPlot.plot.getAxisLabels().setYLabel('Angular Velocity (rad / sec)');
+  gyroPlot.plot.getAxisLabels().setXLabel('Monotonic Reading Time (sec)');
+
+  const gyroX = gyroPlot.addMessageLine(imu, ['gyro_x']);
+  gyroX.setColor(RED);
+  const gyroY = gyroPlot.addMessageLine(imu, ['gyro_y']);
+  gyroY.setColor(GREEN);
+  const gyroZ = gyroPlot.addMessageLine(imu, ['gyro_z']);
+  gyroZ.setColor(BLUE);
+
+  const impliedAccelPlot =
+      aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
+  impliedAccelPlot.plot.getAxisLabels().setTitle('Implied Accelerations');
+  impliedAccelPlot.plot.getAxisLabels().setXLabel(TIME);
+
+  impliedAccelPlot.addMessageLine(localizer, ['model_based', 'implied_accel_z'])
+      .setColor(BLUE);
+  impliedAccelPlot.addMessageLine(localizer, ['model_based', 'implied_accel_y'])
+      .setColor(GREEN);
+  impliedAccelPlot.addMessageLine(localizer, ['model_based', 'implied_accel_x'])
+      .setColor(RED);
+
+  const costPlot =
+      aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
+  costPlot.plot.getAxisLabels().setTitle('Costs');
+  costPlot.plot.getAxisLabels().setXLabel(TIME);
+
+  costPlot.addMessageLine(localizer, ['model_based', 'residual'])
+      .setColor(RED)
+      .setPointSize(0);
+
+  costPlot.addMessageLine(localizer, ['model_based', 'filtered_residual'])
+      .setColor(BLUE)
+      .setPointSize(0);
+
+  costPlot.addMessageLine(localizer, ['model_based', 'velocity_residual'])
+      .setColor(GREEN)
+      .setPointSize(0);
+
+  costPlot.addMessageLine(localizer, ['model_based', 'theta_rate_residual'])
+      .setColor(BROWN)
+      .setPointSize(0);
+
+  costPlot.addMessageLine(localizer, ['model_based', 'accel_residual'])
+      .setColor(CYAN)
+      .setPointSize(0);
+}
diff --git a/y2022/control_loops/localizer/localizer_replay.cc b/y2022/control_loops/localizer/localizer_replay.cc
new file mode 100644
index 0000000..67fb35a
--- /dev/null
+++ b/y2022/control_loops/localizer/localizer_replay.cc
@@ -0,0 +1,119 @@
+
+#include "aos/configuration.h"
+#include "aos/events/logging/log_reader.h"
+#include "aos/events/logging/log_writer.h"
+#include "aos/events/simulated_event_loop.h"
+#include "aos/init.h"
+#include "aos/json_to_flatbuffer.h"
+#include "aos/network/team_number.h"
+#include "y2022/control_loops/localizer/localizer.h"
+#include "y2022/control_loops/localizer/localizer_schema.h"
+#include "gflags/gflags.h"
+#include "y2020/control_loops/drivetrain/drivetrain_base.h"
+
+DEFINE_string(config, "y2020/config.json",
+              "Name of the config file to replay using.");
+DEFINE_int32(team, 7971, "Team number to use for logfile replay.");
+DEFINE_string(output_folder, "/tmp/replayed",
+              "Name of the folder to write replayed logs to.");
+
+class LoggerState {
+ public:
+  LoggerState(aos::logger::LogReader *reader, const aos::Node *node)
+      : event_loop_(
+            reader->event_loop_factory()->MakeEventLoop("logger", node)),
+        namer_(std::make_unique<aos::logger::MultiNodeLogNamer>(
+            absl::StrCat(FLAGS_output_folder, "/", node->name()->string_view(),
+                         "/"),
+            event_loop_.get())),
+        logger_(std::make_unique<aos::logger::Logger>(event_loop_.get())) {
+    event_loop_->SkipTimingReport();
+    event_loop_->SkipAosLog();
+    event_loop_->OnRun([this]() { logger_->StartLogging(std::move(namer_)); });
+  }
+
+ private:
+  std::unique_ptr<aos::EventLoop> event_loop_;
+  std::unique_ptr<aos::logger::LogNamer> namer_;
+  std::unique_ptr<aos::logger::Logger> logger_;
+};
+
+// TODO(james): Currently, this replay produces logfiles that can't be read due
+// to time estimation issues. Pending the active refactorings of the
+// timestamp-related code, fix this.
+int main(int argc, char **argv) {
+  aos::InitGoogle(&argc, &argv);
+
+  aos::network::OverrideTeamNumber(FLAGS_team);
+
+  const aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+      aos::configuration::ReadConfig(FLAGS_config);
+
+  // find logfiles
+  std::vector<std::string> unsorted_logfiles =
+      aos::logger::FindLogs(argc, argv);
+
+  // sort logfiles
+  const std::vector<aos::logger::LogFile> logfiles =
+      aos::logger::SortParts(unsorted_logfiles);
+
+  // open logfiles
+  aos::logger::LogReader reader(logfiles);
+  // Patch in any new channels.
+  // TODO(james): With some of the extra changes I've made recently, this is no
+  // longer adequate for replaying old logfiles. Just stop trying to support old
+  // logs.
+  aos::FlatbufferDetachedBuffer<aos::Configuration> updated_config =
+      aos::configuration::MergeWithConfig(
+          reader.configuration(),
+          aos::configuration::AddSchema(
+              R"channel({
+  "channels": [
+    {
+      "name": "/localizer",
+      "type": "frc971.controls.LocalizerStatus",
+      "source_node": "roborio",
+      "frequency": 2000,
+      "max_size": 2000,
+      "num_senders": 2
+    }
+  ]
+})channel",
+              {aos::FlatbufferVector<reflection::Schema>(
+                  aos::FlatbufferSpan<reflection::Schema>(
+                      frc971::controls::LocalizerStatusSchema()))}));
+
+  auto factory = std::make_unique<aos::SimulatedEventLoopFactory>(
+      &updated_config.message());
+
+  reader.Register(factory.get());
+
+  std::vector<std::unique_ptr<LoggerState>> loggers;
+  // List of nodes to create loggers for (note: currently just roborio; this
+  // code was refactored to allow easily adding new loggers to accommodate
+  // debugging and potential future changes).
+  const std::vector<std::string> nodes_to_log = {"roborio"};
+  for (const std::string &node : nodes_to_log) {
+    loggers.emplace_back(std::make_unique<LoggerState>(
+        &reader, aos::configuration::GetNode(reader.configuration(), node)));
+  }
+
+  const aos::Node *node = nullptr;
+  if (aos::configuration::MultiNode(reader.configuration())) {
+    node = aos::configuration::GetNode(reader.configuration(), "roborio");
+  }
+
+  std::unique_ptr<aos::EventLoop> localizer_event_loop =
+      reader.event_loop_factory()->MakeEventLoop("localizer", node);
+  localizer_event_loop->SkipTimingReport();
+
+  frc971::controls::EventLoopLocalizer localizer(
+      localizer_event_loop.get(),
+      y2020::control_loops::drivetrain::GetDrivetrainConfig());
+
+  reader.event_loop_factory()->Run();
+
+  reader.Deregister();
+
+  return 0;
+}
diff --git a/y2022/control_loops/localizer/localizer_status.fbs b/y2022/control_loops/localizer/localizer_status.fbs
new file mode 100644
index 0000000..6771c5f
--- /dev/null
+++ b/y2022/control_loops/localizer/localizer_status.fbs
@@ -0,0 +1,87 @@
+include "frc971/control_loops/drivetrain/drivetrain_status.fbs";
+
+namespace frc971.controls;
+
+// Stores the state associated with the acceleration-based modelling.
+table AccelBasedState {
+  // x/y position, in meters.
+  x:double (id: 0);
+  y:double (id: 1);
+  // heading, in radians.
+  theta:double (id: 2);
+  // Velocity in X/Y directions, in m/s.
+  velocity_x:double (id: 3);
+  velocity_y:double (id: 4);
+}
+
+// Stores the state associated with the drivetrain model-based state.
+// This model assumes zero lateral motion of the drivetrain.
+table ModelBasedState {
+  // x/y position, in meters.
+  x:double (id: 0);
+  y:double (id: 1);
+  // heading, in radians.
+  theta:double (id: 2);
+  // Expected encoder reading for the left side of the drivetrain, in meters.
+  left_encoder:double (id: 3);
+  // Modelled velocity of the left side of the drivetrain, in meters / second.
+  left_velocity:double (id: 4);
+  // Estimated voltage error, in volts.
+  left_voltage_error:double (id: 5);
+  // Same as the left_* fields, but for the right side of the drivetrain.
+  right_encoder:double (id: 6);
+  right_velocity:double (id: 7);
+  right_voltage_error:double (id: 8);
+}
+
+table ModelBasedStatus {
+  // Current acceleration and model-based states. Depending on using_model,
+  // one of these will be the ground-truth and the other will be calculated
+  // based on it. E.g. if using_model is true, then model_state will be
+  // populated as you'd expect, while accel_state will be populated to be
+  // consistent with model_state (e.g., no lateral motion).
+  accel_state:AccelBasedState (id: 0);
+  model_state:ModelBasedState (id: 1);
+  // using_model indicates whether we are currently in in model-based or
+  // accelerometer-based estimation.
+  using_model:bool (id: 2);
+  // Current residual associated with the amount of inconsistency between
+  // the two models. Will be zero if the drivetrain model is perfectly
+  // consistent with the IMU readings.
+  residual:double (id: 3);
+  // Status from the down estimator.
+  down_estimator:frc971.control_loops.drivetrain.DownEstimatorState (id: 4);
+  // Current ground-truth for x/y/theta. Should match those present in *_state.
+  x:double (id: 5);
+  y:double (id: 6);
+  theta:double (id: 7);
+  // Current accelerations implied by the current accelerometer + down estimator
+  // + yaw readings.
+  implied_accel_x:double (id: 8);
+  implied_accel_y:double (id: 9);
+  implied_accel_z:double (id: 10);
+  // oldest_* are the oldest surviving branches of the model that have just been
+  // running purely on one model.
+  oldest_accel_state:AccelBasedState (id: 11);
+  oldest_model_state:ModelBasedState (id: 12);
+  // Filtered version of the residual field--this is what is actually used by
+  // the code for determining when to swap between modes.
+  filtered_residual:double (id: 13);
+  // Components of the residual. Useful for debugging.
+  velocity_residual:double (id: 14);
+  accel_residual:double (id: 15);
+  theta_rate_residual:double (id: 16);
+  // Number of times we have missed an IMU reading. Should never increase except
+  // *maybe* during startup.
+  clock_resets:int (id: 17);
+}
+
+table LocalizerStatus {
+  model_based:ModelBasedStatus (id: 0);
+  // Whether the IMU is zeroed or not.
+  zeroed:bool (id: 1);
+  // Whether the IMU zeroing is faulted or not.
+  faulted_zero:bool (id: 2);
+}
+
+root_type LocalizerStatus;
diff --git a/y2022/control_loops/localizer/localizer_test.cc b/y2022/control_loops/localizer/localizer_test.cc
new file mode 100644
index 0000000..5857bda
--- /dev/null
+++ b/y2022/control_loops/localizer/localizer_test.cc
@@ -0,0 +1,525 @@
+#include "y2022/control_loops/localizer/localizer.h"
+
+#include "aos/events/simulated_event_loop.h"
+#include "gtest/gtest.h"
+#include "frc971/control_loops/drivetrain/drivetrain_test_lib.h"
+
+namespace frc971::controls::testing {
+typedef ModelBasedLocalizer::ModelState ModelState;
+typedef ModelBasedLocalizer::AccelState AccelState;
+typedef ModelBasedLocalizer::ModelInput ModelInput;
+typedef ModelBasedLocalizer::AccelInput AccelInput;
+namespace {
+constexpr size_t kX = ModelBasedLocalizer::kX;
+constexpr size_t kY = ModelBasedLocalizer::kY;
+constexpr size_t kTheta = ModelBasedLocalizer::kTheta;
+constexpr size_t kVelocityX = ModelBasedLocalizer::kVelocityX;
+constexpr size_t kVelocityY = ModelBasedLocalizer::kVelocityY;
+constexpr size_t kAccelX = ModelBasedLocalizer::kAccelX;
+constexpr size_t kAccelY = ModelBasedLocalizer::kAccelY;
+constexpr size_t kThetaRate = ModelBasedLocalizer::kThetaRate;
+constexpr size_t kLeftEncoder = ModelBasedLocalizer::kLeftEncoder;
+constexpr size_t kLeftVelocity = ModelBasedLocalizer::kLeftVelocity;
+constexpr size_t kLeftVoltageError = ModelBasedLocalizer::kLeftVoltageError;
+constexpr size_t kRightEncoder = ModelBasedLocalizer::kRightEncoder;
+constexpr size_t kRightVelocity = ModelBasedLocalizer::kRightVelocity;
+constexpr size_t kRightVoltageError = ModelBasedLocalizer::kRightVoltageError;
+constexpr size_t kLeftVoltage = ModelBasedLocalizer::kLeftVoltage;
+constexpr size_t kRightVoltage = ModelBasedLocalizer::kRightVoltage;
+}
+
+class LocalizerTest : public ::testing::Test {
+ protected:
+  LocalizerTest()
+      : dt_config_(
+            control_loops::drivetrain::testing::GetTestDrivetrainConfig()),
+        localizer_(dt_config_) {}
+  ModelState CallDiffModel(const ModelState &state, const ModelInput &U) {
+    return localizer_.DiffModel(state, U);
+  }
+
+  AccelState CallDiffAccel(const AccelState &state, const AccelInput &U) {
+    return localizer_.DiffAccel(state, U);
+  }
+
+  const control_loops::drivetrain::DrivetrainConfig<double> dt_config_;
+  ModelBasedLocalizer localizer_;
+
+};
+
+TEST_F(LocalizerTest, AccelIntegrationTest) {
+  AccelState state;
+  state.setZero();
+  AccelInput input;
+  input.setZero();
+
+  EXPECT_EQ(0.0, CallDiffAccel(state, input).norm());
+  // Non-zero x/y/theta states should still result in a zero derivative.
+  state(kX) = 1.0;
+  state(kY) = 1.0;
+  state(kTheta) = 1.0;
+  EXPECT_EQ(0.0, CallDiffAccel(state, input).norm());
+
+  state.setZero();
+  state(kVelocityX) = 1.0;
+  state(kVelocityY) = 2.0;
+  EXPECT_EQ((AccelState() << 1.0, 2.0, 0.0, 0.0, 0.0).finished(),
+            CallDiffAccel(state, input));
+  // Derivatives should be independent of theta.
+  state(kTheta) = M_PI / 2.0;
+  EXPECT_EQ((AccelState() << 1.0, 2.0, 0.0, 0.0, 0.0).finished(),
+            CallDiffAccel(state, input));
+
+  state.setZero();
+  input(kAccelX) = 1.0;
+  input(kAccelY) = 2.0;
+  input(kThetaRate) = 3.0;
+  EXPECT_EQ((AccelState() << 0.0, 0.0, 3.0, 1.0, 2.0).finished(),
+            CallDiffAccel(state, input));
+  state(kTheta) = M_PI / 2.0;
+  EXPECT_EQ((AccelState() << 0.0, 0.0, 3.0, 1.0, 2.0).finished(),
+            CallDiffAccel(state, input));
+}
+
+TEST_F(LocalizerTest, ModelIntegrationTest) {
+  ModelState state;
+  state.setZero();
+  ModelInput input;
+  input.setZero();
+  ModelState diff;
+
+  EXPECT_EQ(0.0, CallDiffModel(state, input).norm());
+  // Non-zero x/y/theta/encoder states should still result in a zero derivative.
+  state(kX) = 1.0;
+  state(kY) = 1.0;
+  state(kTheta) = 1.0;
+  state(kLeftEncoder) = 1.0;
+  state(kRightEncoder) = 1.0;
+  EXPECT_EQ(0.0, CallDiffModel(state, input).norm());
+
+  state.setZero();
+  state(kLeftVelocity) = 1.0;
+  state(kRightVelocity) = 1.0;
+  diff = CallDiffModel(state, input);
+  const ModelState mask_velocities =
+      (ModelState() << 1.0, 1.0, 1.0, 1.0, 0.0, 1.0, 1.0, 0.0, 1.0).finished();
+  EXPECT_EQ(
+      (ModelState() << 1.0, 0.0, 0.0, 1.0, 0.0, 0.0, 1.0, 0.0, 0.0).finished(),
+      diff.cwiseProduct(mask_velocities));
+  EXPECT_EQ(diff(kLeftVelocity), diff(kRightVelocity));
+  EXPECT_GT(0.0, diff(kLeftVelocity));
+  state(kTheta) = M_PI / 2.0;
+  diff = CallDiffModel(state, input);
+  EXPECT_NEAR(0.0,
+              ((ModelState() << 0.0, 1.0, 0.0, 1.0, 0.0, 0.0, 1.0, 0.0, 0.0)
+                   .finished() -
+               diff.cwiseProduct(mask_velocities))
+                  .norm(),
+              1e-12);
+  EXPECT_EQ(diff(kLeftVelocity), diff(kRightVelocity));
+  EXPECT_GT(0.0, diff(kLeftVelocity));
+
+  state.setZero();
+  state(kLeftVelocity) = -1.0;
+  state(kRightVelocity) = 1.0;
+  diff = CallDiffModel(state, input);
+  EXPECT_EQ((ModelState() << 0.0, 0.0, 1.0 / dt_config_.robot_radius, -1.0, 0.0,
+             0.0, 1.0, 0.0, 0.0)
+                .finished(),
+            diff.cwiseProduct(mask_velocities));
+  EXPECT_EQ(-diff(kLeftVelocity), diff(kRightVelocity));
+  EXPECT_LT(0.0, diff(kLeftVelocity));
+
+  state.setZero();
+  input(kLeftVoltage) = 5.0;
+  input(kRightVoltage) = 6.0;
+  diff = CallDiffModel(state, input);
+  EXPECT_EQ(0, diff(kX));
+  EXPECT_EQ(0, diff(kY));
+  EXPECT_EQ(0, diff(kTheta));
+  EXPECT_EQ(0, diff(kLeftEncoder));
+  EXPECT_EQ(0, diff(kRightEncoder));
+  EXPECT_EQ(0, diff(kLeftVoltageError));
+  EXPECT_EQ(0, diff(kRightVoltageError));
+  EXPECT_LT(0, diff(kLeftVelocity));
+  EXPECT_LT(0, diff(kRightVelocity));
+  EXPECT_LT(diff(kLeftVelocity), diff(kRightVelocity));
+
+  state.setZero();
+  state(kLeftVoltageError) = -1.0;
+  state(kRightVoltageError) = -2.0;
+  input(kLeftVoltage) = 1.0;
+  input(kRightVoltage) = 2.0;
+  EXPECT_EQ(ModelState::Zero(), CallDiffModel(state, input));
+}
+
+// Test that the HandleReset does indeed reset the state of the localizer.
+TEST_F(LocalizerTest, LocalizerReset) {
+  aos::monotonic_clock::time_point t = aos::monotonic_clock::epoch();
+  localizer_.HandleReset(t, {1.0, 2.0, 3.0});
+  EXPECT_EQ((Eigen::Vector3d{1.0, 2.0, 3.0}), localizer_.xytheta());
+  localizer_.HandleReset(t, {4.0, 5.0, 6.0});
+  EXPECT_EQ((Eigen::Vector3d{4.0, 5.0, 6.0}), localizer_.xytheta());
+}
+
+// Test that if we are moving only by accelerometer readings (and just assuming
+// zero voltage/encoders) that we initially don't believe it but then latch into
+// following the accelerometer.
+// Note: this test is somewhat sensitive to the exact tuning values used for the
+// filter.
+TEST_F(LocalizerTest, AccelOnly) {
+  const aos::monotonic_clock::time_point start = aos::monotonic_clock::epoch();
+  const std::chrono::microseconds kDt{500};
+  aos::monotonic_clock::time_point t = start - std::chrono::milliseconds(1000);
+  Eigen::Vector3d gyro{0.0, 0.0, 0.0};
+  const Eigen::Vector2d encoders{0.0, 0.0};
+  const Eigen::Vector2d voltages{0.0, 0.0};
+  Eigen::Vector3d accel{1.0, 0.2, 9.80665};
+  Eigen::Vector3d accel_gs = accel / 9.80665;
+  while (t < start) {
+    // Spin to fill up the buffer.
+    localizer_.HandleImu(t, gyro, Eigen::Vector3d::UnitZ(), encoders, voltages);
+    t += kDt;
+  }
+  while (t < start + std::chrono::milliseconds(100)) {
+    localizer_.HandleImu(t, gyro, accel_gs, encoders, voltages);
+    EXPECT_EQ(Eigen::Vector3d::Zero(), localizer_.xytheta());
+    t += kDt;
+  }
+  while (t < start + std::chrono::milliseconds(500)) {
+    // Too lazy to hard-code when the transition happens.
+    localizer_.HandleImu(t, gyro, accel_gs, encoders, voltages);
+    t += kDt;
+  }
+  while (t < start + std::chrono::milliseconds(1000)) {
+    SCOPED_TRACE(t);
+    localizer_.HandleImu(t, gyro, accel_gs, encoders, voltages);
+    const Eigen::Vector3d xytheta = localizer_.xytheta();
+    t += kDt;
+    EXPECT_NEAR(
+        0.5 * accel(0) * std::pow(aos::time::DurationInSeconds(t - start), 2),
+        xytheta(0), 1e-4);
+    EXPECT_NEAR(
+        0.5 * accel(1) * std::pow(aos::time::DurationInSeconds(t - start), 2),
+        xytheta(1), 1e-4);
+    EXPECT_EQ(0.0, xytheta(2));
+  }
+
+  ASSERT_NEAR(1.0, localizer_.accel_state()(kVelocityX), 1e-10);
+  ASSERT_NEAR(0.2, localizer_.accel_state()(kVelocityY), 1e-10);
+
+  // Start going in a cirlce, and confirm that we
+  // handle things correctly. We rotate the accelerometer readings by 90 degrees
+  // and then leave them constant, which should make it look like we are going
+  // around in a circle.
+  accel = Eigen::Vector3d{-accel(1), accel(0), 9.80665};
+  accel_gs = accel / 9.80665;
+  // v^2 / r = a
+  // w * r = v
+  // v^2 / v * w = a
+  // w = a / v
+  const double omega = accel.topRows<2>().norm() /
+                       std::hypot(localizer_.accel_state()(kVelocityX),
+                                  localizer_.accel_state()(kVelocityY));
+  gyro << 0.0, 0.0, omega;
+  // Due to the magic of math, omega works out to be 1.0 after having run at the
+  // acceleration for one second.
+  ASSERT_NEAR(1.0, omega, 1e-10);
+  // Yes, we could save some operations here, but let's be at least somewhat
+  // clear about what we're doing...
+  const double radius = accel.topRows<2>().norm() / (omega * omega);
+  const Eigen::Vector2d center = localizer_.xytheta().topRows<2>() +
+                                 accel.topRows<2>().normalized() * radius;
+  const double initial_theta = std::atan2(-accel(1), -accel(0));
+
+  std::chrono::microseconds one_revolution_time(
+      static_cast<int>(2 * M_PI / omega * 1e6));
+
+  aos::monotonic_clock::time_point circle_start = t;
+
+  while (t < circle_start + one_revolution_time) {
+    SCOPED_TRACE(t);
+    localizer_.HandleImu(t, gyro, accel_gs, encoders, voltages);
+    t += kDt;
+    const double t_circle = aos::time::DurationInSeconds(t - circle_start);
+    ASSERT_NEAR(t_circle * omega, localizer_.xytheta()(2), 1e-5);
+    const double theta_circle = t_circle * omega + initial_theta;
+    const Eigen::Vector2d offset =
+        radius *
+        Eigen::Vector2d{std::cos(theta_circle), std::sin(theta_circle)};
+    const Eigen::Vector2d expected = center + offset;
+    const Eigen::Vector2d estimated = localizer_.xytheta().topRows<2>();
+    const Eigen::Vector2d implied_offset = estimated - center;
+    const double implied_theta =
+        std::atan2(implied_offset.y(), implied_offset.x());
+    VLOG(1) << "center: " << center.transpose() << " radius " << radius
+            << "\nlocalizer " << localizer_.xytheta().transpose()
+            << " t_circle " << t_circle << " omega " << omega << " theta "
+            << theta_circle << "\noffset " << offset.transpose()
+            << "\nexpected " << expected.transpose() << "\nimplied offset "
+            << implied_offset << " implied_theta " << implied_theta << "\nvel "
+            << localizer_.accel_state()(kVelocityX) << ", "
+            << localizer_.accel_state()(kVelocityY);
+    ASSERT_NEAR(0.0, (expected - localizer_.xytheta().topRows<2>()).norm(),
+                1e-2);
+  }
+
+  // Set accelerometer back to zero and confirm that we recover (the
+  // implementation decays the accelerometer speeds to zero when still, so
+  // should recover).
+  while (t <
+         circle_start + one_revolution_time + std::chrono::milliseconds(3000)) {
+    localizer_.HandleImu(t, Eigen::Vector3d::Zero(), Eigen::Vector3d::UnitZ(),
+                         encoders, voltages);
+    t += kDt;
+  }
+  const Eigen::Vector3d final_pos = localizer_.xytheta();
+  localizer_.HandleImu(t, Eigen::Vector3d::Zero(), Eigen::Vector3d::UnitZ(),
+                       encoders, voltages);
+  ASSERT_NEAR(0.0, (final_pos - localizer_.xytheta()).norm(), 1e-10);
+}
+
+using control_loops::drivetrain::Output;
+
+class EventLoopLocalizerTest : public ::testing::Test {
+ protected:
+  EventLoopLocalizerTest()
+      : configuration_(aos::configuration::ReadConfig("y2022/config.json")),
+        event_loop_factory_(&configuration_.message()),
+        roborio_node_(
+            aos::configuration::GetNode(&configuration_.message(), "roborio")),
+        imu_node_(
+            aos::configuration::GetNode(&configuration_.message(), "imu")),
+        dt_config_(
+            control_loops::drivetrain::testing::GetTestDrivetrainConfig()),
+        localizer_event_loop_(
+            event_loop_factory_.MakeEventLoop("localizer", imu_node_)),
+        localizer_(localizer_event_loop_.get(), dt_config_),
+        drivetrain_plant_event_loop_(event_loop_factory_.MakeEventLoop(
+            "drivetrain_plant", roborio_node_)),
+        drivetrain_plant_imu_event_loop_(
+            event_loop_factory_.MakeEventLoop("drivetrain_plant", imu_node_)),
+        drivetrain_plant_(drivetrain_plant_event_loop_.get(),
+                          drivetrain_plant_imu_event_loop_.get(), dt_config_,
+                          std::chrono::microseconds(500)),
+        roborio_test_event_loop_(
+            event_loop_factory_.MakeEventLoop("test", roborio_node_)),
+        imu_test_event_loop_(
+            event_loop_factory_.MakeEventLoop("test", imu_node_)),
+        logger_test_event_loop_(
+            event_loop_factory_.GetNodeEventLoopFactory("logger")
+                ->MakeEventLoop("test")),
+        output_sender_(
+            roborio_test_event_loop_->MakeSender<Output>("/drivetrain")),
+        output_fetcher_(roborio_test_event_loop_->MakeFetcher<LocalizerOutput>(
+            "/localizer")),
+        status_fetcher_(
+            imu_test_event_loop_->MakeFetcher<LocalizerStatus>("/localizer")) {
+    aos::TimerHandler *timer = roborio_test_event_loop_->AddTimer([this]() {
+      auto builder = output_sender_.MakeBuilder();
+      auto output_builder = builder.MakeBuilder<Output>();
+      output_builder.add_left_voltage(output_voltages_(0));
+      output_builder.add_right_voltage(output_voltages_(1));
+      builder.CheckOk(builder.Send(output_builder.Finish()));
+    });
+    roborio_test_event_loop_->OnRun([timer, this]() {
+      timer->Setup(roborio_test_event_loop_->monotonic_now(),
+                   std::chrono::milliseconds(5));
+    });
+    // Get things zeroed.
+    event_loop_factory_.RunFor(std::chrono::seconds(10));
+    CHECK(status_fetcher_.Fetch());
+    CHECK(status_fetcher_->zeroed());
+  }
+
+  aos::FlatbufferDetachedBuffer<aos::Configuration> configuration_;
+  aos::SimulatedEventLoopFactory event_loop_factory_;
+  const aos::Node *const roborio_node_;
+  const aos::Node *const imu_node_;
+  const control_loops::drivetrain::DrivetrainConfig<double> dt_config_;
+  std::unique_ptr<aos::EventLoop> localizer_event_loop_;
+  EventLoopLocalizer localizer_;
+
+  std::unique_ptr<aos::EventLoop> drivetrain_plant_event_loop_;
+  std::unique_ptr<aos::EventLoop> drivetrain_plant_imu_event_loop_;
+  control_loops::drivetrain::testing::DrivetrainSimulation drivetrain_plant_;
+
+  std::unique_ptr<aos::EventLoop> roborio_test_event_loop_;
+  std::unique_ptr<aos::EventLoop> imu_test_event_loop_;
+  std::unique_ptr<aos::EventLoop> logger_test_event_loop_;
+
+  aos::Sender<Output> output_sender_;
+  aos::Fetcher<LocalizerOutput> output_fetcher_;
+  aos::Fetcher<LocalizerStatus> status_fetcher_;
+
+  Eigen::Vector2d output_voltages_ = Eigen::Vector2d::Zero();
+};
+
+TEST_F(EventLoopLocalizerTest, Nominal) {
+  output_voltages_ << 1.0, 1.0;
+  event_loop_factory_.RunFor(std::chrono::seconds(2));
+  drivetrain_plant_.set_accel_sin_magnitude(0.01);
+  CHECK(output_fetcher_.Fetch());
+  CHECK(status_fetcher_.Fetch());
+  // The two can be different because they may've been sent at different times.
+  ASSERT_NEAR(output_fetcher_->x(), status_fetcher_->model_based()->x(), 1e-6);
+  ASSERT_NEAR(output_fetcher_->y(), status_fetcher_->model_based()->y(), 1e-6);
+  ASSERT_NEAR(output_fetcher_->theta(), status_fetcher_->model_based()->theta(),
+              1e-6);
+  ASSERT_LT(0.1, output_fetcher_->x());
+  ASSERT_NEAR(0.0, output_fetcher_->y(), 1e-10);
+  ASSERT_NEAR(0.0, output_fetcher_->theta(), 1e-10);
+  ASSERT_TRUE(status_fetcher_->has_model_based());
+  ASSERT_TRUE(status_fetcher_->model_based()->using_model());
+  ASSERT_LT(0.1, status_fetcher_->model_based()->accel_state()->velocity_x());
+  ASSERT_NEAR(0.0, status_fetcher_->model_based()->accel_state()->velocity_y(),
+              1e-10);
+  ASSERT_NEAR(
+      0.0, status_fetcher_->model_based()->model_state()->left_voltage_error(),
+      1e-1);
+  ASSERT_NEAR(
+      0.0, status_fetcher_->model_based()->model_state()->right_voltage_error(),
+      1e-1);
+}
+
+TEST_F(EventLoopLocalizerTest, Reverse) {
+  output_voltages_ << -4.0, -4.0;
+  drivetrain_plant_.set_accel_sin_magnitude(0.01);
+  event_loop_factory_.RunFor(std::chrono::seconds(2));
+  CHECK(output_fetcher_.Fetch());
+  CHECK(status_fetcher_.Fetch());
+  // The two can be different because they may've been sent at different times.
+  ASSERT_NEAR(output_fetcher_->x(), status_fetcher_->model_based()->x(), 1e-6);
+  ASSERT_NEAR(output_fetcher_->y(), status_fetcher_->model_based()->y(), 1e-6);
+  ASSERT_NEAR(output_fetcher_->theta(), status_fetcher_->model_based()->theta(),
+              1e-6);
+  ASSERT_GT(-0.1, output_fetcher_->x());
+  ASSERT_NEAR(0.0, output_fetcher_->y(), 1e-10);
+  ASSERT_NEAR(0.0, output_fetcher_->theta(), 1e-10);
+  ASSERT_TRUE(status_fetcher_->has_model_based());
+  ASSERT_TRUE(status_fetcher_->model_based()->using_model());
+  ASSERT_GT(-0.1, status_fetcher_->model_based()->accel_state()->velocity_x());
+  ASSERT_NEAR(0.0, status_fetcher_->model_based()->accel_state()->velocity_y(),
+              1e-10);
+  ASSERT_NEAR(
+      0.0, status_fetcher_->model_based()->model_state()->left_voltage_error(),
+      1e-1);
+  ASSERT_NEAR(
+      0.0, status_fetcher_->model_based()->model_state()->right_voltage_error(),
+      1e-1);
+}
+
+TEST_F(EventLoopLocalizerTest, SpinInPlace) {
+  output_voltages_ << 4.0, -4.0;
+  event_loop_factory_.RunFor(std::chrono::seconds(2));
+  CHECK(output_fetcher_.Fetch());
+  CHECK(status_fetcher_.Fetch());
+  // The two can be different because they may've been sent at different times.
+  ASSERT_NEAR(output_fetcher_->x(), status_fetcher_->model_based()->x(), 1e-6);
+  ASSERT_NEAR(output_fetcher_->y(), status_fetcher_->model_based()->y(), 1e-6);
+  ASSERT_NEAR(output_fetcher_->theta(), status_fetcher_->model_based()->theta(),
+              1e-1);
+  ASSERT_NEAR(0.0, output_fetcher_->x(), 1e-10);
+  ASSERT_NEAR(0.0, output_fetcher_->y(), 1e-10);
+  ASSERT_LT(0.1, std::abs(output_fetcher_->theta()));
+  ASSERT_TRUE(status_fetcher_->has_model_based());
+  ASSERT_TRUE(status_fetcher_->model_based()->using_model());
+  ASSERT_NEAR(0.0, status_fetcher_->model_based()->accel_state()->velocity_x(),
+              1e-10);
+  ASSERT_NEAR(0.0, status_fetcher_->model_based()->accel_state()->velocity_y(),
+              1e-10);
+  ASSERT_NEAR(-status_fetcher_->model_based()->model_state()->left_velocity(),
+              status_fetcher_->model_based()->model_state()->right_velocity(),
+              1e-3);
+  ASSERT_NEAR(
+      0.0, status_fetcher_->model_based()->model_state()->left_voltage_error(),
+      1e-1);
+  ASSERT_NEAR(
+      0.0, status_fetcher_->model_based()->model_state()->right_voltage_error(),
+      1e-1);
+  ASSERT_NEAR(0.0, status_fetcher_->model_based()->residual(), 1e-3);
+}
+
+TEST_F(EventLoopLocalizerTest, Curve) {
+  output_voltages_ << 2.0, 4.0;
+  event_loop_factory_.RunFor(std::chrono::seconds(2));
+  CHECK(output_fetcher_.Fetch());
+  CHECK(status_fetcher_.Fetch());
+  // The two can be different because they may've been sent at different times.
+  ASSERT_NEAR(output_fetcher_->x(), status_fetcher_->model_based()->x(), 1e-2);
+  ASSERT_NEAR(output_fetcher_->y(), status_fetcher_->model_based()->y(), 1e-2);
+  ASSERT_NEAR(output_fetcher_->theta(), status_fetcher_->model_based()->theta(),
+              1e-1);
+  ASSERT_LT(0.1, output_fetcher_->x());
+  ASSERT_LT(0.1, output_fetcher_->y());
+  ASSERT_LT(0.1, std::abs(output_fetcher_->theta()));
+  ASSERT_TRUE(status_fetcher_->has_model_based());
+  ASSERT_TRUE(status_fetcher_->model_based()->using_model());
+  ASSERT_LT(0.0, status_fetcher_->model_based()->accel_state()->velocity_x());
+  ASSERT_LT(0.0, status_fetcher_->model_based()->accel_state()->velocity_y());
+  ASSERT_NEAR(
+      0.0, status_fetcher_->model_based()->model_state()->left_voltage_error(),
+      1e-1);
+  ASSERT_NEAR(
+      0.0, status_fetcher_->model_based()->model_state()->right_voltage_error(),
+      1e-1);
+  ASSERT_NEAR(0.0, status_fetcher_->model_based()->residual(), 1e-1)
+      << aos::FlatbufferToJson(status_fetcher_.get(), {.multi_line = true});
+}
+
+// Tests that small amounts of voltage error are handled by the model-based
+// half of the localizer.
+TEST_F(EventLoopLocalizerTest, VoltageError) {
+  output_voltages_ << 0.0, 0.0;
+  drivetrain_plant_.set_left_voltage_offset(2.0);
+  drivetrain_plant_.set_right_voltage_offset(2.0);
+  drivetrain_plant_.set_accel_sin_magnitude(0.01);
+
+  event_loop_factory_.RunFor(std::chrono::seconds(2));
+  CHECK(output_fetcher_.Fetch());
+  CHECK(status_fetcher_.Fetch());
+  // Should still be using the model, but have a non-trivial residual.
+  ASSERT_TRUE(status_fetcher_->model_based()->using_model());
+  ASSERT_LT(0.1, status_fetcher_->model_based()->residual())
+      << aos::FlatbufferToJson(status_fetcher_.get(), {.multi_line = true});
+
+  // Afer running for a while, voltage error terms should converge and result in
+  // low residuals.
+  event_loop_factory_.RunFor(std::chrono::seconds(10));
+  CHECK(output_fetcher_.Fetch());
+  CHECK(status_fetcher_.Fetch());
+  ASSERT_TRUE(status_fetcher_->model_based()->using_model());
+  ASSERT_NEAR(
+      2.0, status_fetcher_->model_based()->model_state()->left_voltage_error(),
+      0.1)
+      << aos::FlatbufferToJson(status_fetcher_.get(), {.multi_line = true});
+  ASSERT_NEAR(
+      2.0, status_fetcher_->model_based()->model_state()->right_voltage_error(),
+      0.1)
+      << aos::FlatbufferToJson(status_fetcher_.get(), {.multi_line = true});
+  ASSERT_GT(0.01, status_fetcher_->model_based()->residual())
+      << aos::FlatbufferToJson(status_fetcher_.get(), {.multi_line = true});
+}
+
+// Tests that large amounts of voltage error force us into the
+// acceleration-based localizer.
+TEST_F(EventLoopLocalizerTest, HighVoltageError) {
+  output_voltages_ << 0.0, 0.0;
+  drivetrain_plant_.set_left_voltage_offset(200.0);
+  drivetrain_plant_.set_right_voltage_offset(200.0);
+  drivetrain_plant_.set_accel_sin_magnitude(0.01);
+
+  event_loop_factory_.RunFor(std::chrono::seconds(2));
+  CHECK(output_fetcher_.Fetch());
+  CHECK(status_fetcher_.Fetch());
+  // Should still be using the model, but have a non-trivial residual.
+  ASSERT_FALSE(status_fetcher_->model_based()->using_model());
+  ASSERT_LT(0.1, status_fetcher_->model_based()->residual())
+      << aos::FlatbufferToJson(status_fetcher_.get(), {.multi_line = true});
+  ASSERT_NEAR(drivetrain_plant_.state()(0),
+              status_fetcher_->model_based()->x(), 1.0);
+  ASSERT_NEAR(drivetrain_plant_.state()(1),
+              status_fetcher_->model_based()->y(), 1e-6);
+}
+
+}  // namespace frc91::controls::testing
diff --git a/y2022/control_loops/python/BUILD b/y2022/control_loops/python/BUILD
index e0b0daa..54bce63 100644
--- a/y2022/control_loops/python/BUILD
+++ b/y2022/control_loops/python/BUILD
@@ -49,9 +49,68 @@
 )
 
 py_library(
+    name = "catapult_lib",
+    srcs = [
+        "catapult_lib.py",
+    ],
+    target_compatible_with = ["@platforms//cpu:x86_64"],
+    deps = [
+        "//frc971/control_loops/python:controls",
+        "@matplotlib_repo//:matplotlib3",
+    ],
+)
+
+py_binary(
+    name = "catapult",
+    srcs = [
+        "catapult.py",
+    ],
+    legacy_create_init = False,
+    target_compatible_with = ["@platforms//cpu:x86_64"],
+    deps = [
+        ":catapult_lib",
+        ":python_init",
+        "//external:python-gflags",
+        "//external:python-glog",
+    ],
+)
+
+py_binary(
+    name = "intake",
+    srcs = [
+        "intake.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:angular_system",
+        "//frc971/control_loops/python:controls",
+    ],
+)
+
+py_binary(
+    name = "turret",
+    srcs = [
+        "turret.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:angular_system",
+        "//frc971/control_loops/python:controls",
+    ],
+)
+
+py_library(
     name = "python_init",
     srcs = ["__init__.py"],
     target_compatible_with = ["@platforms//os:linux"],
     visibility = ["//visibility:public"],
-    deps = ["//y2020/control_loops:python_init"],
+    deps = ["//y2022/control_loops:python_init"],
 )
diff --git a/y2022/control_loops/python/catapult.py b/y2022/control_loops/python/catapult.py
new file mode 100755
index 0000000..bb8d74d
--- /dev/null
+++ b/y2022/control_loops/python/catapult.py
@@ -0,0 +1,84 @@
+#!/usr/bin/python3
+
+from frc971.control_loops.python import control_loop
+from frc971.control_loops.python import controls
+import numpy
+import math
+import sys
+import math
+from y2022.control_loops.python import catapult_lib
+from matplotlib import pylab
+
+import gflags
+import glog
+
+FLAGS = gflags.FLAGS
+
+gflags.DEFINE_bool('plot', True, 'If true, plot the loop response.')
+
+ball_mass = 0.25
+ball_diameter = 9.5 * 0.0254
+lever = 17.5 * 0.0254
+
+G = (14.0 / 72.0) * (12.0 / 33.0)
+
+
+def AddResistance(motor, resistance):
+    motor.resistance += resistance
+    return motor
+
+J_ball = 1.5 * ball_mass * lever * lever
+# Assuming carbon fiber, calculate the mass of the bar.
+M_bar = (1750 * lever * 0.0254 * 0.0254 * (1.0 - (1 - 0.07)**2.0))
+# And the moment of inertia.
+J_bar = 1.0 / 3.0 * M_bar * lever**2.0
+
+# Do the same for a theoretical cup.  Assume a 40 thou thick carbon cup.
+M_cup = (1750 * 0.0254 * 0.04 * 2 * math.pi * (ball_diameter / 2.)**2.0)
+J_cup = M_cup * lever**2.0 + M_cup * (ball_diameter / 2.)**2.0
+
+print("J ball", ball_mass * lever * lever)
+print("J bar", J_bar)
+print("bar mass", M_bar)
+print("J cup", J_cup)
+print("cup mass", M_cup)
+
+J = (J_ball + J_bar + J_cup * 1.5)
+print("J", J)
+
+kFinisher = catapult_lib.CatapultParams(
+    name='Finisher',
+    motor=AddResistance(control_loop.NMotor(control_loop.Falcon(), 2), 0.03),
+    G=G,
+    J=J,
+    lever=lever,
+    q_pos=0.01,
+    q_vel=10.0,
+    q_voltage=4.0,
+    r_pos=0.01,
+    controller_poles=[.93],
+    dt=0.0005)
+
+
+def main(argv):
+    # Do all our math with a lower voltage so we have headroom.
+    U = numpy.matrix([[9.0]])
+    print("For G:", G, " max speed ", catapult_lib.MaxSpeed(params=kFinisher, U=U, final_position = math.pi / 2.0))
+
+    if FLAGS.plot:
+        catapult_lib.PlotShot(kFinisher, U, final_position = math.pi / 4.0)
+
+        gs = []
+        speed = []
+        for i in numpy.linspace(0.01, 0.15, 150):
+            kFinisher.G = i
+            gs.append(kFinisher.G)
+            speed.append(catapult_lib.MaxSpeed(params=kFinisher, U=U, final_position = math.pi / 2.0))
+        pylab.plot(gs, speed, label = "max_speed")
+        pylab.show()
+        return 0
+
+
+if __name__ == '__main__':
+    argv = FLAGS(sys.argv)
+    sys.exit(main(argv))
diff --git a/y2022/control_loops/python/catapult_lib.py b/y2022/control_loops/python/catapult_lib.py
new file mode 100644
index 0000000..256793a
--- /dev/null
+++ b/y2022/control_loops/python/catapult_lib.py
@@ -0,0 +1,308 @@
+from frc971.control_loops.python import control_loop
+from frc971.control_loops.python import controls
+import numpy
+from matplotlib import pylab
+
+import gflags
+import glog
+
+
+class CatapultParams(object):
+    def __init__(self,
+                 name,
+                 motor,
+                 G,
+                 J,
+                 lever,
+                 q_pos,
+                 q_vel,
+                 q_voltage,
+                 r_pos,
+                 controller_poles,
+                 dt=0.00505):
+        self.name = name
+        self.motor = motor
+        self.G = G
+        self.J = J
+        self.lever = lever
+        self.q_pos = q_pos
+        self.q_vel = q_vel
+        self.q_voltage = q_voltage
+        self.r_pos = r_pos
+        self.dt = dt
+        self.controller_poles = controller_poles
+
+
+class VelocityCatapult(control_loop.HybridControlLoop):
+    def __init__(self, params, name="Catapult"):
+        super(VelocityCatapult, self).__init__(name=name)
+        self.params = params
+        # Set Motor
+        self.motor = self.params.motor
+        # Gear ratio
+        self.G = self.params.G
+        # Moment of inertia of the catapult wheel in kg m^2
+        self.J = self.params.J + self.motor.motor_inertia / (self.G**2.0)
+        # Control loop time step
+        self.dt = self.params.dt
+
+        # State feedback matrices
+        # [angular velocity]
+        self.A_continuous = numpy.matrix([[
+            -self.motor.Kt / self.motor.Kv /
+            (self.J * self.G * self.G * self.motor.resistance)
+        ]])
+        self.B_continuous = numpy.matrix(
+            [[self.motor.Kt / (self.J * self.G * self.motor.resistance)]])
+        self.C = numpy.matrix([[1]])
+        self.D = numpy.matrix([[0]])
+
+        self.A, self.B = self.ContinuousToDiscrete(self.A_continuous,
+                                                   self.B_continuous, self.dt)
+
+        self.PlaceControllerPoles(self.params.controller_poles)
+
+        # Generated controller not used.
+        self.PlaceObserverPoles([0.3])
+
+        self.U_max = numpy.matrix([[12.0]])
+        self.U_min = numpy.matrix([[-12.0]])
+
+        qff_vel = 8.0
+        self.Qff = numpy.matrix([[1.0 / (qff_vel**2.0)]])
+
+        self.Kff = controls.TwoStateFeedForwards(self.B, self.Qff)
+
+        glog.debug('K: %s', str(self.K))
+        glog.debug('Poles: %s',
+                   str(numpy.linalg.eig(self.A - self.B * self.K)[0]))
+
+
+class Catapult(VelocityCatapult):
+    def __init__(self, params, name="Catapult"):
+        super(Catapult, self).__init__(params, name=name)
+
+        self.A_continuous_unaugmented = self.A_continuous
+        self.B_continuous_unaugmented = self.B_continuous
+
+        self.A_continuous = numpy.matrix(numpy.zeros((2, 2)))
+        self.A_continuous[1:2, 1:2] = self.A_continuous_unaugmented
+        self.A_continuous[0, 1] = 1
+
+        self.B_continuous = numpy.matrix(numpy.zeros((2, 1)))
+        self.B_continuous[1:2, 0] = self.B_continuous_unaugmented
+
+        # State feedback matrices
+        # [position, angular velocity]
+        self.C = numpy.matrix([[1, 0]])
+        self.D = numpy.matrix([[0]])
+
+        self.A, self.B = self.ContinuousToDiscrete(self.A_continuous,
+                                                   self.B_continuous, self.dt)
+
+        rpl = 0.45
+        ipl = 0.07
+        self.PlaceObserverPoles([rpl + 1j * ipl, rpl - 1j * ipl])
+
+        self.K_unaugmented = self.K
+        self.K = numpy.matrix(numpy.zeros((1, 2)))
+        self.K[0, 1:2] = self.K_unaugmented
+        self.Kff_unaugmented = self.Kff
+        self.Kff = numpy.matrix(numpy.zeros((1, 2)))
+        self.Kff[0, 1:2] = self.Kff_unaugmented
+
+        self.InitializeState()
+
+
+class IntegralCatapult(Catapult):
+    def __init__(self, params, name="IntegralCatapult"):
+        super(IntegralCatapult, self).__init__(params, name=name)
+
+        self.A_continuous_unaugmented = self.A_continuous
+        self.B_continuous_unaugmented = self.B_continuous
+
+        self.A_continuous = numpy.matrix(numpy.zeros((3, 3)))
+        self.A_continuous[0:2, 0:2] = self.A_continuous_unaugmented
+        self.A_continuous[0:2, 2] = self.B_continuous_unaugmented
+
+        self.B_continuous = numpy.matrix(numpy.zeros((3, 1)))
+        self.B_continuous[0:2, 0] = self.B_continuous_unaugmented
+
+        # states
+        # [position, velocity, voltage_error]
+        self.C_unaugmented = self.C
+        self.C = numpy.matrix(numpy.zeros((1, 3)))
+        self.C[0:1, 0:2] = self.C_unaugmented
+
+        glog.debug('A_continuous %s' % str(self.A_continuous))
+        glog.debug('B_continuous %s' % str(self.B_continuous))
+        glog.debug('C %s' % str(self.C))
+
+        self.A, self.B = self.ContinuousToDiscrete(self.A_continuous,
+                                                   self.B_continuous, self.dt)
+
+        glog.debug('A %s' % str(self.A))
+        glog.debug('B %s' % str(self.B))
+
+        q_pos = self.params.q_pos
+        q_vel = self.params.q_vel
+        q_voltage = self.params.q_voltage
+        self.Q_continuous = numpy.matrix([[(q_pos**2.0), 0.0,
+                                           0.0], [0.0, (q_vel**2.0), 0.0],
+                                          [0.0, 0.0, (q_voltage**2.0)]])
+
+        r_pos = self.params.r_pos
+        self.R_continuous = numpy.matrix([[(r_pos**2.0)]])
+
+        _, _, self.Q, self.R = controls.kalmd(
+            A_continuous=self.A_continuous,
+            B_continuous=self.B_continuous,
+            Q_continuous=self.Q_continuous,
+            R_continuous=self.R_continuous,
+            dt=self.dt)
+
+        glog.debug('Q_discrete %s' % (str(self.Q)))
+        glog.debug('R_discrete %s' % (str(self.R)))
+
+        self.KalmanGain, self.P_steady_state = controls.kalman(
+            A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
+        self.L = self.A * self.KalmanGain
+
+        self.K_unaugmented = self.K
+        self.K = numpy.matrix(numpy.zeros((1, 3)))
+        self.K[0, 0:2] = self.K_unaugmented
+        self.K[0, 2] = 1
+        self.Kff_unaugmented = self.Kff
+        self.Kff = numpy.matrix(numpy.zeros((1, 3)))
+        self.Kff[0, 0:2] = self.Kff_unaugmented
+
+        self.InitializeState()
+
+
+def MaxSpeed(params, U, final_position):
+    """Runs the catapult plant with an initial condition and goal.
+
+    Args:
+        catapult: Catapult object to use.
+        goal: goal state.
+        iterations: Number of timesteps to run the model for.
+        controller_catapult: Catapult object to get K from, or None if we should
+             use catapult.
+        observer_catapult: Catapult object to use for the observer, or None if we
+            should use the actual state.
+    """
+
+    # Various lists for graphing things.
+    catapult = Catapult(params, params.name)
+    controller_catapult = IntegralCatapult(params, params.name)
+    observer_catapult = IntegralCatapult(params, params.name)
+    vbat = 12.0
+
+    while True:
+        X_hat = catapult.X
+        if catapult.X[0, 0] > final_position:
+            return catapult.X[1, 0] * params.lever
+
+        if observer_catapult is not None:
+            X_hat = observer_catapult.X_hat
+
+        U[0, 0] = numpy.clip(U[0, 0], -vbat, vbat)
+
+        if observer_catapult is not None:
+            observer_catapult.Y = catapult.Y
+            observer_catapult.CorrectHybridObserver(U)
+
+        applied_U = U.copy()
+        catapult.Update(applied_U)
+
+        if observer_catapult is not None:
+            observer_catapult.PredictHybridObserver(U, catapult.dt)
+
+
+def PlotShot(params, U, final_position):
+    """Runs the catapult plant with an initial condition and goal.
+
+    Args:
+        catapult: Catapult object to use.
+        goal: goal state.
+        iterations: Number of timesteps to run the model for.
+        controller_catapult: Catapult object to get K from, or None if we should
+             use catapult.
+        observer_catapult: Catapult object to use for the observer, or None if we
+            should use the actual state.
+    """
+
+    # Various lists for graphing things.
+    t = []
+    x = []
+    x_hat = []
+    v = []
+    w_hat = []
+    v_hat = []
+    a = []
+    u = []
+    offset = []
+
+    catapult = Catapult(params, params.name)
+    controller_catapult = IntegralCatapult(params, params.name)
+    observer_catapult = IntegralCatapult(params, params.name)
+    vbat = 12.0
+
+    if t:
+        initial_t = t[-1] + catapult.dt
+    else:
+        initial_t = 0
+
+    for i in range(10000):
+        X_hat = catapult.X
+        if catapult.X[0, 0] > final_position:
+            break
+
+        if observer_catapult is not None:
+            X_hat = observer_catapult.X_hat
+            x_hat.append(observer_catapult.X_hat[0, 0])
+            w_hat.append(observer_catapult.X_hat[1, 0])
+            v_hat.append(observer_catapult.X_hat[1, 0] * params.lever)
+
+        U[0, 0] = numpy.clip(U[0, 0], -vbat, vbat)
+        x.append(catapult.X[0, 0])
+
+        if v:
+            last_v = v[-1]
+        else:
+            last_v = 0
+
+        v.append(catapult.X[1, 0])
+        a.append((v[-1] - last_v) / catapult.dt)
+
+        if observer_catapult is not None:
+            observer_catapult.Y = catapult.Y
+            observer_catapult.CorrectHybridObserver(U)
+            offset.append(observer_catapult.X_hat[2, 0])
+
+        catapult.Update(U)
+
+        if observer_catapult is not None:
+            observer_catapult.PredictHybridObserver(U, catapult.dt)
+
+        t.append(initial_t + i * catapult.dt)
+        u.append(U[0, 0])
+
+    pylab.subplot(3, 1, 1)
+    pylab.plot(t, v, label='v')
+    pylab.plot(t, x_hat, label='x_hat')
+    pylab.plot(t, v, label='v')
+    pylab.plot(t, v_hat, label='v_hat')
+    pylab.plot(t, w_hat, label='w_hat')
+    pylab.legend()
+
+    pylab.subplot(3, 1, 2)
+    pylab.plot(t, u, label='u')
+    pylab.plot(t, offset, label='voltage_offset')
+    pylab.legend()
+
+    pylab.subplot(3, 1, 3)
+    pylab.plot(t, a, label='a')
+    pylab.legend()
+
+    pylab.show()
diff --git a/y2022/control_loops/python/drivetrain.py b/y2022/control_loops/python/drivetrain.py
index 7b8dc49..59b9651 100644
--- a/y2022/control_loops/python/drivetrain.py
+++ b/y2022/control_loops/python/drivetrain.py
@@ -16,11 +16,11 @@
     J=6.0,
     mass=58.0,
     # TODO(austin): Measure radius a bit better.
-    robot_radius= 0.39,
-    wheel_radius= 3/39.37,
+    robot_radius=0.39,
+    wheel_radius=2.5 * 0.0254,
     motor_type=control_loop.Falcon(),
-    num_motors = 3,
-    G=8.0 / 80.0,
+    num_motors=3,
+    G=(14.0 / 54.0) * (22.0 / 56.0),
     q_pos=0.24,
     q_vel=2.5,
     efficiency=0.80,
diff --git a/y2022/control_loops/python/intake.py b/y2022/control_loops/python/intake.py
new file mode 100644
index 0000000..e5030e5
--- /dev/null
+++ b/y2022/control_loops/python/intake.py
@@ -0,0 +1,55 @@
+#!/usr/bin/python3
+
+from aos.util.trapezoid_profile import TrapezoidProfile
+from frc971.control_loops.python import control_loop
+from frc971.control_loops.python import angular_system
+from frc971.control_loops.python import controls
+import numpy
+import sys
+from matplotlib import pylab
+import gflags
+import glog
+
+FLAGS = gflags.FLAGS
+
+try:
+    gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+except gflags.DuplicateFlagError:
+    pass
+
+kIntake = angular_system.AngularSystemParams(
+    name='Intake',
+    motor=control_loop.Falcon(),
+    # TODO(Milo): Change gear ratios when we have all of them
+    G=0.02,
+    J=0.34,
+    q_pos=0.40,
+    q_vel=20.0,
+    kalman_q_pos=0.12,
+    kalman_q_vel=2.0,
+    kalman_q_voltage=4.0,
+    kalman_r_position=0.05,
+    radius=13 * 0.0254)
+
+
+def main(argv):
+    if FLAGS.plot:
+        R = numpy.matrix([[numpy.pi / 2.0], [0.0]])
+        angular_system.PlotKick(kIntake, R)
+        angular_system.PlotMotion(kIntake, R)
+
+    # Write the generated constants out to a file.
+    if len(argv) != 5:
+        glog.fatal(
+            'Expected .h file name and .cc file name for the intake and integral intake.'
+        )
+    else:
+        namespaces = ['y2022', 'control_loops', 'superstructure', 'intake']
+        angular_system.WriteAngularSystem(kIntake, argv[1:3], argv[3:5],
+                                          namespaces)
+
+
+if __name__ == '__main__':
+    argv = FLAGS(sys.argv)
+    glog.init()
+    sys.exit(main(argv))
diff --git a/y2022/control_loops/python/turret.py b/y2022/control_loops/python/turret.py
new file mode 100644
index 0000000..83ba4b3
--- /dev/null
+++ b/y2022/control_loops/python/turret.py
@@ -0,0 +1,54 @@
+#!/usr/bin/python3
+
+from aos.util.trapezoid_profile import TrapezoidProfile
+from frc971.control_loops.python import control_loop
+from frc971.control_loops.python import angular_system
+from frc971.control_loops.python import controls
+import numpy
+import sys
+from matplotlib import pylab
+import gflags
+import glog
+
+FLAGS = gflags.FLAGS
+
+try:
+    gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+except gflags.DuplicateFlagError:
+    pass
+
+kTurret = angular_system.AngularSystemParams(
+    name='Turret',
+    motor=control_loop.Falcon(),
+    G=0.01,
+    J=2.0,
+    q_pos=0.40,
+    q_vel=20.0,
+    kalman_q_pos=0.12,
+    kalman_q_vel=2.0,
+    kalman_q_voltage=4.0,
+    kalman_r_position=0.05,
+    radius=24 * 0.0254)
+
+
+def main(argv):
+    if FLAGS.plot:
+        R = numpy.matrix([[numpy.pi], [0.0]])
+        angular_system.PlotKick(kTurret, R)
+        angular_system.PlotMotion(kTurret, R)
+
+    # Write the generated constants out to a file.
+    if len(argv) != 5:
+        glog.fatal(
+            'Expected .h file name and .cc file name for the turret and integral turret.'
+        )
+    else:
+        namespaces = ['y2022', 'control_loops', 'superstructure', 'turret']
+        angular_system.WriteAngularSystem(kTurret, argv[1:3], argv[3:5],
+                                          namespaces)
+
+
+if __name__ == '__main__':
+    argv = FLAGS(sys.argv)
+    glog.init()
+    sys.exit(main(argv))
diff --git a/y2022/control_loops/superstructure/intake/BUILD b/y2022/control_loops/superstructure/intake/BUILD
new file mode 100644
index 0000000..f6e5be0
--- /dev/null
+++ b/y2022/control_loops/superstructure/intake/BUILD
@@ -0,0 +1,34 @@
+package(default_visibility = ["//y2022:__subpackages__"])
+
+genrule(
+    name = "genrule_intake",
+    outs = [
+        "intake_plant.h",
+        "intake_plant.cc",
+        "integral_intake_plant.h",
+        "integral_intake_plant.cc",
+    ],
+    cmd = "$(location //y2022/control_loops/python:intake) $(OUTS)",
+    target_compatible_with = ["@platforms//os:linux"],
+    tools = [
+        "//y2022/control_loops/python:intake",
+    ],
+)
+
+cc_library(
+    name = "intake_plants",
+    srcs = [
+        "intake_plant.cc",
+        "integral_intake_plant.cc",
+    ],
+    hdrs = [
+        "intake_plant.h",
+        "integral_intake_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",
+    ],
+)
diff --git a/y2022/localizer/BUILD b/y2022/localizer/BUILD
new file mode 100644
index 0000000..c2afa55
--- /dev/null
+++ b/y2022/localizer/BUILD
@@ -0,0 +1,32 @@
+cc_library(
+    name = "imu",
+    srcs = [
+        "imu.cc",
+    ],
+    hdrs = [
+        "imu.h",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    deps = [
+        "//aos/events:epoll",
+        "//aos/events:shm_event_loop",
+        "//aos/util:crc32",
+        "//frc971/wpilib:imu_batch_fbs",
+        "//frc971/wpilib:imu_fbs",
+        "//y2022:constants",
+        "@com_github_google_glog//:glog",
+        "@com_google_absl//absl/types:span",
+    ],
+)
+
+cc_binary(
+    name = "imu_main",
+    srcs = ["imu_main.cc"],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//visibility:public"],
+    deps = [
+        ":imu",
+        "//aos:init",
+        "//aos/events:shm_event_loop",
+    ],
+)
diff --git a/y2022/localizer/imu.cc b/y2022/localizer/imu.cc
new file mode 100644
index 0000000..eb76e00
--- /dev/null
+++ b/y2022/localizer/imu.cc
@@ -0,0 +1,168 @@
+#include "y2022/localizer/imu.h"
+
+#include "aos/util/crc32.h"
+#include "glog/logging.h"
+#include "y2022/constants.h"
+
+namespace y2022::localizer {
+
+namespace {
+
+constexpr size_t kReadSize = 50;
+constexpr double kGyroScale = 1 / 655360.0 / 360.0 * (2 * M_PI);
+constexpr double kAccelScale = 1 / 26756268.0 / 9.80665;
+constexpr double kTempScale = 0.1;
+
+}  // namespace
+
+Imu::Imu(aos::ShmEventLoop *event_loop)
+    : event_loop_(event_loop),
+      imu_sender_(
+          event_loop_->MakeSender<frc971::IMUValuesBatch>("/localizer")) {
+  event_loop->SetRuntimeRealtimePriority(30);
+  imu_fd_ = open("/dev/adis16505", O_RDONLY | O_NONBLOCK);
+  PCHECK(imu_fd_ != -1) << ": Failed to open SPI device for IMU.";
+  aos::internal::EPoll *epoll = event_loop_->epoll();
+  epoll->OnReadable(imu_fd_, [this]() {
+    uint8_t buf[kReadSize];
+    ssize_t read_len = read(imu_fd_, buf, kReadSize);
+    // TODO: Do we care about gracefully handling EAGAIN or anything else?
+    // This should only get called when there is data.
+    PCHECK(read_len != -1);
+    CHECK_EQ(read_len, static_cast<ssize_t>(kReadSize))
+        << ": Read incorrect number of bytes.";
+
+    auto sender = imu_sender_.MakeBuilder();
+
+    const flatbuffers::Offset<frc971::IMUValues> values_offset =
+        ProcessReading(sender.fbb(), absl::Span(buf, kReadSize));
+    const flatbuffers::Offset<
+        flatbuffers::Vector<flatbuffers::Offset<frc971::IMUValues>>>
+        readings_offset = sender.fbb()->CreateVector(&values_offset, 1);
+    frc971::IMUValuesBatch::Builder batch_builder =
+        sender.MakeBuilder<frc971::IMUValuesBatch>();
+    batch_builder.add_readings(readings_offset);
+    imu_sender_.CheckOk(sender.Send(batch_builder.Finish()));
+  });
+}
+
+flatbuffers::Offset<frc971::IMUValues> Imu::ProcessReading(
+    flatbuffers::FlatBufferBuilder *fbb, const absl::Span<uint8_t> message) {
+  absl::Span<const uint8_t> buf = message;
+
+  uint64_t driver_timestamp;
+  memcpy(&driver_timestamp, buf.data(), sizeof(driver_timestamp));
+  buf = buf.subspan(8);
+
+  uint16_t diag_stat;
+  memcpy(&diag_stat, buf.data(), sizeof(diag_stat));
+  buf = buf.subspan(2);
+
+  double x_gyro = ConvertValue32(buf, kGyroScale);
+  buf = buf.subspan(4);
+  double y_gyro = ConvertValue32(buf, kGyroScale);
+  buf = buf.subspan(4);
+  double z_gyro = ConvertValue32(buf, kGyroScale);
+  buf = buf.subspan(4);
+  double x_accel = ConvertValue32(buf, kAccelScale);
+  buf = buf.subspan(4);
+  double y_accel = ConvertValue32(buf, kAccelScale);
+  buf = buf.subspan(4);
+  double z_accel = ConvertValue32(buf, kAccelScale);
+  buf = buf.subspan(4);
+  double temp = ConvertValue16(buf, kTempScale);
+  buf = buf.subspan(2);
+  uint16_t data_counter;
+  memcpy(&data_counter, buf.data(), sizeof(data_counter));
+  buf = buf.subspan(2);
+  uint32_t pico_timestamp;
+  memcpy(&pico_timestamp, buf.data(), sizeof(pico_timestamp));
+  buf = buf.subspan(4);
+  int16_t encoder1_count;
+  memcpy(&encoder1_count, buf.data(), sizeof(encoder1_count));
+  buf = buf.subspan(2);
+  int16_t encoder2_count;
+  memcpy(&encoder2_count, buf.data(), sizeof(encoder2_count));
+  buf = buf.subspan(2);
+  uint32_t checksum;
+  memcpy(&checksum, buf.data(), sizeof(checksum));
+  buf = buf.subspan(4);
+
+  CHECK(buf.empty()) << "Have leftover bytes: " << buf.size();
+
+  u_int32_t calculated_checksum = aos::ComputeCrc32(message.subspan(8, 38));
+
+  if (checksum != calculated_checksum) {
+    this->failed_checksums_++;
+  }
+
+  const auto diag_stat_offset = PackDiagStat(fbb, diag_stat);
+
+  frc971::IMUValues::Builder imu_builder(*fbb);
+
+  if (checksum == calculated_checksum) {
+    constexpr uint16_t kChecksumMismatch = 1 << 0;
+    bool imu_checksum_matched = !(diag_stat & kChecksumMismatch);
+
+    // data from the IMU packet
+    if (imu_checksum_matched) {
+      imu_builder.add_gyro_x(x_gyro);
+      imu_builder.add_gyro_y(y_gyro);
+      imu_builder.add_gyro_z(z_gyro);
+
+      imu_builder.add_accelerometer_x(x_accel);
+      imu_builder.add_accelerometer_y(y_accel);
+      imu_builder.add_accelerometer_z(z_accel);
+
+      imu_builder.add_temperature(temp);
+
+      imu_builder.add_data_counter(data_counter);
+    }
+
+    // extra data from the pico
+    imu_builder.add_pico_timestamp_us(pico_timestamp);
+    imu_builder.add_left_encoder(
+        constants::Values::DrivetrainEncoderToMeters(encoder1_count));
+    imu_builder.add_right_encoder(
+        constants::Values::DrivetrainEncoderToMeters(encoder2_count));
+    imu_builder.add_previous_reading_diag_stat(diag_stat_offset);
+  }
+
+  // extra data from us
+  imu_builder.add_monotonic_timestamp_ns(driver_timestamp);
+  imu_builder.add_failed_checksums(failed_checksums_);
+  imu_builder.add_checksum_failed(checksum != calculated_checksum);
+
+  return imu_builder.Finish();
+}
+
+flatbuffers::Offset<frc971::ADIS16470DiagStat> Imu::PackDiagStat(
+    flatbuffers::FlatBufferBuilder *fbb, uint16_t value) {
+  frc971::ADIS16470DiagStat::Builder diag_stat_builder(*fbb);
+  diag_stat_builder.add_clock_error(value & (1 << 7));
+  diag_stat_builder.add_memory_failure(value & (1 << 6));
+  diag_stat_builder.add_sensor_failure(value & (1 << 5));
+  diag_stat_builder.add_standby_mode(value & (1 << 4));
+  diag_stat_builder.add_spi_communication_error(value & (1 << 3));
+  diag_stat_builder.add_flash_memory_update_error(value & (1 << 2));
+  diag_stat_builder.add_data_path_overrun(value & (1 << 1));
+  diag_stat_builder.add_checksum_mismatch(value & (1 << 0));
+  return diag_stat_builder.Finish();
+}
+
+double Imu::ConvertValue32(absl::Span<const uint8_t> data,
+                           double lsb_per_output) {
+  int32_t value;
+  memcpy(&value, data.data(), sizeof(value));
+  return static_cast<double>(value) * lsb_per_output;
+}
+
+double Imu::ConvertValue16(absl::Span<const uint8_t> data,
+                           double lsb_per_output) {
+  int16_t value;
+  memcpy(&value, data.data(), sizeof(value));
+  return static_cast<double>(value) * lsb_per_output;
+}
+
+Imu::~Imu() { PCHECK(0 == close(imu_fd_)); }
+}  // namespace y2022::localizer
diff --git a/y2022/localizer/imu.h b/y2022/localizer/imu.h
new file mode 100644
index 0000000..cd45710
--- /dev/null
+++ b/y2022/localizer/imu.h
@@ -0,0 +1,31 @@
+#ifndef Y2022_LOCALIZER_IMU_H_
+#define Y2022_LOCALIZER_IMU_H_
+#include "aos/events/shm_event_loop.h"
+#include "frc971/wpilib/imu_batch_generated.h"
+#include "y2022/constants.h"
+
+namespace y2022::localizer {
+
+// Reads IMU packets from the kernel driver which reads them over spi
+// from the Raspberry Pi Pico on the IMU board.
+class Imu {
+ public:
+  Imu(aos::ShmEventLoop *event_loop);
+  ~Imu();
+
+ private:
+  flatbuffers::Offset<frc971::ADIS16470DiagStat> PackDiagStat(
+      flatbuffers::FlatBufferBuilder *fbb, uint16_t value);
+  flatbuffers::Offset<frc971::IMUValues> ProcessReading(
+      flatbuffers::FlatBufferBuilder *fbb, absl::Span<uint8_t> buf);
+  double ConvertValue32(absl::Span<const uint8_t> data, double lsb_per_output);
+  double ConvertValue16(absl::Span<const uint8_t> data, double lsb_per_output);
+
+  aos::ShmEventLoop *event_loop_;
+  aos::Sender<frc971::IMUValuesBatch> imu_sender_;
+  int imu_fd_;
+
+  uint failed_checksums_ = 0;
+};
+}  // namespace y2022::localizer
+#endif  // Y2022_LOCALIZER_IMU_H_
diff --git a/y2022/localizer/imu_main.cc b/y2022/localizer/imu_main.cc
new file mode 100644
index 0000000..bba2dd7
--- /dev/null
+++ b/y2022/localizer/imu_main.cc
@@ -0,0 +1,19 @@
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "y2022/localizer/imu.h"
+
+DEFINE_string(config, "config.json", "Path to the config file to use.");
+
+int main(int argc, char *argv[]) {
+  aos::InitGoogle(&argc, &argv);
+
+  aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+      aos::configuration::ReadConfig(FLAGS_config);
+
+  aos::ShmEventLoop event_loop(&config.message());
+  y2022::localizer::Imu imu(&event_loop);
+
+  event_loop.Run();
+
+  return 0;
+}
diff --git a/y2022/vision/blob_detector.cc b/y2022/vision/blob_detector.cc
index a732762..96d7ffd 100644
--- a/y2022/vision/blob_detector.cc
+++ b/y2022/vision/blob_detector.cc
@@ -9,26 +9,40 @@
 #include "opencv2/features2d.hpp"
 #include "opencv2/imgproc.hpp"
 
-DEFINE_uint64(green_delta, 50,
-              "Required difference between green pixels vs. red and blue");
+DEFINE_uint64(red_delta, 100,
+              "Required difference between green pixels vs. red");
+DEFINE_uint64(blue_delta, 50,
+              "Required difference between green pixels vs. blue");
+
 DEFINE_bool(use_outdoors, false,
             "If true, change thresholds to handle outdoor illumination");
+DEFINE_uint64(outdoors_red_delta, 100,
+              "Difference between green pixels vs. red, when outdoors");
+DEFINE_uint64(outdoors_blue_delta, 15,
+              "Difference between green pixels vs. blue, when outdoors");
 
 namespace y2022 {
 namespace vision {
 
-cv::Mat BlobDetector::ThresholdImage(cv::Mat rgb_image) {
-  cv::Mat binarized_image(cv::Size(rgb_image.cols, rgb_image.rows), CV_8UC1);
-  for (int row = 0; row < rgb_image.rows; row++) {
-    for (int col = 0; col < rgb_image.cols; col++) {
-      cv::Vec3b pixel = rgb_image.at<cv::Vec3b>(row, col);
+cv::Mat BlobDetector::ThresholdImage(cv::Mat bgr_image) {
+  size_t red_delta = FLAGS_red_delta;
+  size_t blue_delta = FLAGS_blue_delta;
+
+  if (FLAGS_use_outdoors) {
+    red_delta = FLAGS_outdoors_red_delta;
+    red_delta = FLAGS_outdoors_blue_delta;
+  }
+
+  cv::Mat binarized_image(cv::Size(bgr_image.cols, bgr_image.rows), CV_8UC1);
+  for (int row = 0; row < bgr_image.rows; row++) {
+    for (int col = 0; col < bgr_image.cols; col++) {
+      cv::Vec3b pixel = bgr_image.at<cv::Vec3b>(row, col);
       uint8_t blue = pixel.val[0];
       uint8_t green = pixel.val[1];
       uint8_t red = pixel.val[2];
       // Simple filter that looks for green pixels sufficiently brigher than
       // red and blue
-      if ((green > blue + FLAGS_green_delta) &&
-          (green > red + FLAGS_green_delta)) {
+      if ((green > blue + blue_delta) && (green > red + red_delta)) {
         binarized_image.at<uint8_t>(row, col) = 255;
       } else {
         binarized_image.at<uint8_t>(row, col) = 0;
@@ -143,15 +157,26 @@
   }
 
   double DistanceTo(cv::Point2d p) const {
-    // Translate the point so that the circle orgin can be (0, 0)
-    const auto p_prime = cv::Point2d(p.y - center.y, p.x - center.x);
+    const auto p_prime = TranslateToOrigin(p);
     // Now, the distance is simply the difference between distance from the
     // origin to p' and the radius.
     return std::abs(cv::norm(p_prime) - radius);
   }
 
-  // Inverted because y-coordinates go backwards
-  bool OnTopHalf(cv::Point2d p) const { return p.y <= center.y; }
+  bool InAngleRange(cv::Point2d p, double theta_min, double theta_max) const {
+    auto p_prime = TranslateToOrigin(p);
+    // Flip the y because y values go downwards.
+    p_prime.y *= -1;
+    const double theta = std::atan2(p_prime.y, p_prime.x);
+    return (theta >= theta_min && theta <= theta_max);
+  }
+
+ private:
+  // Translate the point on the circle
+  // as if the circle's center is the origin (0,0)
+  cv::Point2d TranslateToOrigin(cv::Point2d p) const {
+    return cv::Point2d(p.x - center.x, p.y - center.y);
+  }
 };
 
 }  // namespace
@@ -169,24 +194,24 @@
     // when the camera is the farthest from the target, at the field corner.
     // We can solve for the pitch of the blob:
     // blob_pitch = atan((height_tape - height_camera) / depth) + camera_pitch
-    // The triangle with the height of the tape above the camera and the camera
-    // depth is similar to the one with the focal length in y pixels and the y
-    // coordinate offset from the center of the image.
-    // Therefore y_offset = focal_length_y * tan(blob_pitch), and
-    // y = -(y_offset - offset_y)
+    // The triangle with the height of the tape above the camera and the
+    // camera depth is similar to the one with the focal length in y pixels
+    // and the y coordinate offset from the center of the image. Therefore
+    // y_offset = focal_length_y * tan(blob_pitch), and y = -(y_offset -
+    // offset_y)
     constexpr int kMaxY = 400;
     constexpr double kTapeAspectRatio = 5.0 / 2.0;
-    constexpr double kAspectRatioThreshold = 1.5;
+    constexpr double kAspectRatioThreshold = 1.6;
     constexpr double kMinArea = 10;
-    constexpr size_t kMinPoints = 6;
+    constexpr size_t kMinNumPoints = 6;
 
     // Remove all blobs that are at the bottom of the image, have a different
-    // aspect ratio than the tape, or have too little area or points
-    // TODO(milind): modify to take into account that blobs will be on the side.
+    // aspect ratio than the tape, or have too little area or points.
     if ((stats_it->centroid.y <= kMaxY) &&
         (std::abs(kTapeAspectRatio - stats_it->aspect_ratio) <
          kAspectRatioThreshold) &&
-        (stats_it->area >= kMinArea) && (stats_it->num_points >= kMinPoints)) {
+        (stats_it->area >= kMinArea) &&
+        (stats_it->num_points >= kMinNumPoints)) {
       filtered_blobs.push_back(*blob_it);
       filtered_stats.push_back(*stats_it);
     }
@@ -196,6 +221,9 @@
 
   // Threshold for mean distance from a blob centroid to a circle.
   constexpr double kCircleDistanceThreshold = 5.0;
+  // We should only expect to see blobs between these angles on a circle.
+  constexpr double kMinBlobAngle = M_PI / 3;
+  constexpr double kMaxBlobAngle = M_PI - kMinBlobAngle;
   std::vector<std::vector<cv::Point>> blob_circle;
   std::vector<cv::Point2d> centroids;
 
@@ -230,16 +258,20 @@
         continue;
       }
 
-      // Only try to fit points to this circle if all of these are on the top
-      // half, like how the blobs should be
-      if (circle->OnTopHalf(current_centroids[0]) &&
-          circle->OnTopHalf(current_centroids[1]) &&
-          circle->OnTopHalf(current_centroids[2])) {
+      // Only try to fit points to this circle if all of these are between
+      // certain angles.
+      if (circle->InAngleRange(current_centroids[0], kMinBlobAngle,
+                               kMaxBlobAngle) &&
+          circle->InAngleRange(current_centroids[1], kMinBlobAngle,
+                               kMaxBlobAngle) &&
+          circle->InAngleRange(current_centroids[2], kMinBlobAngle,
+                               kMaxBlobAngle)) {
         for (size_t m = 0; m < filtered_blobs.size(); m++) {
           // Add this blob to the list if it is close to the circle, is on the
           // top half,  and isn't one of the other blobs
           if ((m != i) && (m != j) && (m != k) &&
-              circle->OnTopHalf(filtered_stats[m].centroid) &&
+              circle->InAngleRange(filtered_stats[m].centroid, kMinBlobAngle,
+                                   kMaxBlobAngle) &&
               (circle->DistanceTo(filtered_stats[m].centroid) <
                kCircleDistanceThreshold)) {
             current_blobs.emplace_back(filtered_blobs[m]);
@@ -293,10 +325,10 @@
   cv::circle(view_image, centroid, 3, cv::Scalar(255, 255, 0), cv::FILLED);
 }
 
-void BlobDetector::ExtractBlobs(cv::Mat rgb_image,
+void BlobDetector::ExtractBlobs(cv::Mat bgr_image,
                                 BlobDetector::BlobResult *blob_result) {
   auto start = aos::monotonic_clock::now();
-  blob_result->binarized_image = ThresholdImage(rgb_image);
+  blob_result->binarized_image = ThresholdImage(bgr_image);
   blob_result->unfiltered_blobs = FindBlobs(blob_result->binarized_image);
   blob_result->blob_stats = ComputeStats(blob_result->unfiltered_blobs);
   auto filtered_pair =
@@ -304,9 +336,9 @@
   blob_result->filtered_blobs = filtered_pair.first;
   blob_result->centroid = filtered_pair.second;
   auto end = aos::monotonic_clock::now();
-  LOG(INFO) << "Blob detection elapsed time: "
-            << std::chrono::duration<double, std::milli>(end - start).count()
-            << " ms";
+  VLOG(2) << "Blob detection elapsed time: "
+          << std::chrono::duration<double, std::milli>(end - start).count()
+          << " ms";
 }
 
 }  // namespace vision
diff --git a/y2022/vision/blob_detector.h b/y2022/vision/blob_detector.h
index 4077e2c..d263d32 100644
--- a/y2022/vision/blob_detector.h
+++ b/y2022/vision/blob_detector.h
@@ -28,7 +28,7 @@
   // Given an image, threshold it to find "green" pixels
   // Input: Color image
   // Output: Grayscale (binarized) image with green pixels set to 255
-  static cv::Mat ThresholdImage(cv::Mat rgb_image);
+  static cv::Mat ThresholdImage(cv::Mat bgr_image);
 
   // Given binary image, extract blobs
   static std::vector<std::vector<cv::Point>> FindBlobs(cv::Mat threshold_image);
@@ -52,7 +52,7 @@
       const std::vector<std::vector<cv::Point>> &unfiltered_blobs,
       const std::vector<BlobStats> &blob_stats, cv::Point centroid);
 
-  static void ExtractBlobs(cv::Mat rgb_image, BlobResult *blob_result);
+  static void ExtractBlobs(cv::Mat bgr_image, BlobResult *blob_result);
 };
 }  // namespace vision
 }  // namespace y2022
diff --git a/y2022/vision/calib_files/calibration_pi-971-1_cam-22-01_2022-02-12_14-35_00.000000000.json b/y2022/vision/calib_files/calibration_pi-971-1_cam-22-01_2022-02-12_14-35_00.000000000.json
new file mode 100644
index 0000000..3c30b15
--- /dev/null
+++ b/y2022/vision/calib_files/calibration_pi-971-1_cam-22-01_2022-02-12_14-35_00.000000000.json
@@ -0,0 +1,24 @@
+{
+ "node_name": "pi1",
+ "team_number": 971,
+ "intrinsics": [
+  391.63916,
+  0.0,
+  312.691162,
+  0.0,
+  391.535889,
+  267.138672,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "dist_coeffs": [
+  0.121374,
+  -0.203352,
+  0.000325,
+  0.002694,
+  0.054089
+ ],
+ "calibration_timestamp": 1635611589630802881,
+ "camera_id": "22-01"
+}
diff --git a/y2022/vision/calib_files/calibration_pi-971-1_cam-22-02_2022-01-28_05-35-16.002911868.json b/y2022/vision/calib_files/calibration_pi-971-1_cam-22-02_2022-01-28_05-35-16.002911868.json
new file mode 100644
index 0000000..b147867
--- /dev/null
+++ b/y2022/vision/calib_files/calibration_pi-971-1_cam-22-02_2022-01-28_05-35-16.002911868.json
@@ -0,0 +1,24 @@
+{
+ "node_name": "pi1",
+ "team_number": 971,
+ "intrinsics": [
+  390.833618,
+  0.0,
+  298.229218,
+  0.0,
+  390.547882,
+  251.143417,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "dist_coeffs": [
+  0.120491,
+  -0.190643,
+  0.000534,
+  -0.000345,
+  0.029808
+ ],
+ "calibration_timestamp": 1643348116002911868,
+ "camera_id": "22-02"
+}
\ No newline at end of file
diff --git a/y2022/vision/calib_files/calibration_pi-971-1_cam-22-03_2022-02-12_16-53-00.000000000.json b/y2022/vision/calib_files/calibration_pi-971-1_cam-22-03_2022-02-12_16-53-00.000000000.json
new file mode 100644
index 0000000..a107065
--- /dev/null
+++ b/y2022/vision/calib_files/calibration_pi-971-1_cam-22-03_2022-02-12_16-53-00.000000000.json
@@ -0,0 +1,24 @@
+{
+ "node_name": "pi1",
+ "team_number": 971,
+ "intrinsics": [
+  388.182281,
+  0.0,
+  306.279083,
+  0.0,
+  388.440582,
+  224.480484,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "dist_coeffs": [
+  0.129443,
+  -0.225948,
+  0.001234,
+  -0.000004,
+  0.068937
+ ],
+ "calibration_timestamp": 1643342760319632865,
+ "camera_id": "22-03"
+}
diff --git a/y2022/vision/calib_files/calibration_pi-971-1_cam-22-04_2022-01-28_05-26-43.135661745.json b/y2022/vision/calib_files/calibration_pi-971-1_cam-22-04_2022-01-28_05-26-43.135661745.json
new file mode 100755
index 0000000..8c19c46
--- /dev/null
+++ b/y2022/vision/calib_files/calibration_pi-971-1_cam-22-04_2022-01-28_05-26-43.135661745.json
@@ -0,0 +1,24 @@
+{
+ "node_name": "pi1",
+ "team_number": 971,
+ "intrinsics": [
+  386.619232,
+  0.0,
+  335.525116,
+  0.0,
+  386.309601,
+  225.775742,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "dist_coeffs": [
+  0.130693,
+  -0.238688,
+  0.002466,
+  -0.00017,
+  0.083145
+ ],
+ "calibration_timestamp": 1643347603135661745,
+ "camera_id": "22-04"
+}
\ No newline at end of file
diff --git a/y2022/vision/calib_files/calibration_pi-971-1_cam-22-05_2022-02-16_20-40-00.000000000.json b/y2022/vision/calib_files/calibration_pi-971-1_cam-22-05_2022-02-16_20-40-00.000000000.json
new file mode 100755
index 0000000..a5ebf82
--- /dev/null
+++ b/y2022/vision/calib_files/calibration_pi-971-1_cam-22-05_2022-02-16_20-40-00.000000000.json
@@ -0,0 +1,24 @@
+{
+ "node_name": "pi1",
+ "team_number": 971,
+ "intrinsics": [
+  387.791046,
+  0.0,
+  360.276276,
+  0.0,
+  387.214264,
+  235.913925,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "dist_coeffs": [
+  0.132322,
+  -0.247507,
+  0.001326,
+  0.002151,
+  0.098543
+ ],
+ "calibration_timestamp": 1643348271146848848,
+ "camera_id": "22-05"
+}
diff --git a/y2022/vision/calib_files/calibration_pi-971-1_cam-22-06_2022-02-16_20-54-00.000000000.json b/y2022/vision/calib_files/calibration_pi-971-1_cam-22-06_2022-02-16_20-54-00.000000000.json
new file mode 100755
index 0000000..71aaf02
--- /dev/null
+++ b/y2022/vision/calib_files/calibration_pi-971-1_cam-22-06_2022-02-16_20-54-00.000000000.json
@@ -0,0 +1,24 @@
+{
+ "node_name": "pi1",
+ "team_number": 971,
+ "intrinsics": [
+  389.730774,
+  0.0,
+  329.825134,
+  0.0,
+  389.599243,
+  205.222931,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "dist_coeffs": [
+  0.12185,
+  -0.214579,
+  -0.00013,
+  0.000629,
+  0.066571
+ ],
+ "calibration_timestamp": 1643348049373070054,
+ "camera_id": "22-06"
+}
diff --git a/y2022/vision/calib_files/calibration_pi-971-1_cam-22-07_2022-02-16_21-20-00.000000000.json b/y2022/vision/calib_files/calibration_pi-971-1_cam-22-07_2022-02-16_21-20-00.000000000.json
new file mode 100755
index 0000000..27ed863
--- /dev/null
+++ b/y2022/vision/calib_files/calibration_pi-971-1_cam-22-07_2022-02-16_21-20-00.000000000.json
@@ -0,0 +1,24 @@
+{
+ "node_name": "pi1",
+ "team_number": 971,
+ "intrinsics": [
+  388.062378,
+  0.0,
+  333.890381,
+  0.0,
+  388.149048,
+  212.644363,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "dist_coeffs": [
+  0.123399,
+  -0.21765,
+  -0.00085,
+  0.000694,
+  0.067006
+ ],
+ "calibration_timestamp": 1643348078845387555,
+ "camera_id": "22-07"
+}
diff --git a/y2022/vision/camera_definition.py b/y2022/vision/camera_definition.py
index a45c704..30057a5 100644
--- a/y2022/vision/camera_definition.py
+++ b/y2022/vision/camera_definition.py
@@ -48,6 +48,7 @@
         self.turret_ext = None
         self.node_name = ""
         self.team_number = -1
+        self.camera_id = ""
         self.timestamp = 0
 
 
@@ -144,6 +145,10 @@
 
             team_number = calib_dict["team_number"]
             node_name = calib_dict["node_name"]
+            camera_id = "UNKNOWN"
+            if "camera_id" in calib_dict:
+                camera_id = calib_dict["camera_id"]
+
             camera_matrix = np.asarray(calib_dict["intrinsics"]).reshape(
                 (3, 3))
             dist_coeffs = np.asarray(calib_dict["dist_coeffs"]).reshape((1, 5))
@@ -158,6 +163,7 @@
 
             camera_params.node_name = node_name
             camera_params.team_number = team_number
+            camera_params.camera_id = camera_id
             camera_params.camera_int.camera_matrix = copy.copy(camera_matrix)
             camera_params.camera_int.dist_coeffs = copy.copy(dist_coeffs)
             camera_list.append(camera_params)
diff --git a/y2022/vision/camera_reader.cc b/y2022/vision/camera_reader.cc
index db87cb0..abce18c 100644
--- a/y2022/vision/camera_reader.cc
+++ b/y2022/vision/camera_reader.cc
@@ -124,8 +124,8 @@
       // that can be sent in a second.
       std::this_thread::sleep_for(std::chrono::milliseconds(50));
       LOG(INFO) << "Reading file " << file;
-      cv::Mat rgb_image = cv::imread(file.c_str());
-      ProcessImage(rgb_image);
+      cv::Mat bgr_image = cv::imread(file.c_str());
+      ProcessImage(bgr_image);
     }
     event_loop_->Exit();
     return;
diff --git a/y2022/vision/camera_reader_main.cc b/y2022/vision/camera_reader_main.cc
index f1c5fdf..52ee51a 100644
--- a/y2022/vision/camera_reader_main.cc
+++ b/y2022/vision/camera_reader_main.cc
@@ -6,7 +6,8 @@
 // bazel run //y2022/vision:camera_reader -- --config y2022/config.json
 //   --override_hostname pi-7971-1  --ignore_timestamps true
 DEFINE_string(config, "config.json", "Path to the config file to use.");
-DEFINE_uint32(exposure, 5, "Exposure time, in 100us increments");
+DEFINE_uint32(exposure, 5,
+              "Exposure time, in 100us increments; 0 implies auto exposure");
 
 namespace y2022 {
 namespace vision {
@@ -33,7 +34,9 @@
   }
 
   V4L2Reader v4l2_reader(&event_loop, "/dev/video0");
-  v4l2_reader.SetExposure(FLAGS_exposure);
+  if (FLAGS_exposure > 0) {
+    v4l2_reader.SetExposure(FLAGS_exposure);
+  }
 
   CameraReader camera_reader(&event_loop, &calibration_data.message(),
                              &v4l2_reader);
diff --git a/y2022/vision/create_calib_file.py b/y2022/vision/create_calib_file.py
index de9f65d..6b24d28 100644
--- a/y2022/vision/create_calib_file.py
+++ b/y2022/vision/create_calib_file.py
@@ -44,13 +44,9 @@
 
 
 def main():
-
-    camera_calib_list = None
-
-    output_path = sys.argv[1]
-
     camera_calib_list = camera_definition.load_camera_definitions()
 
+    output_path = sys.argv[1]
     glog.debug("Writing file to %s", output_path)
 
     fbb = flatbuffers.Builder(0)
diff --git a/y2022/vision/viewer.cc b/y2022/vision/viewer.cc
index 6ee6144..2a6f0a6 100644
--- a/y2022/vision/viewer.cc
+++ b/y2022/vision/viewer.cc
@@ -76,11 +76,11 @@
   // Create color image:
   cv::Mat image_color_mat(cv::Size(image->cols(), image->rows()), CV_8UC2,
                           (void *)image->data()->data());
-  cv::Mat rgb_image(cv::Size(image->cols(), image->rows()), CV_8UC3);
-  cv::cvtColor(image_color_mat, rgb_image, cv::COLOR_YUV2BGR_YUYV);
+  cv::Mat bgr_image(cv::Size(image->cols(), image->rows()), CV_8UC3);
+  cv::cvtColor(image_color_mat, bgr_image, cv::COLOR_YUV2BGR_YUYV);
 
   if (!FLAGS_capture.empty()) {
-    cv::imwrite(FLAGS_capture, rgb_image);
+    cv::imwrite(FLAGS_capture, bgr_image);
     return false;
   }
 
@@ -100,15 +100,15 @@
     cv::imshow("blobs", ret_image);
   }
 
-  cv::imshow("image", rgb_image);
+  cv::imshow("image", bgr_image);
 
   int keystroke = cv::waitKey(1);
   if ((keystroke & 0xFF) == static_cast<int>('c')) {
     // Convert again, to get clean image
-    cv::cvtColor(image_color_mat, rgb_image, cv::COLOR_YUV2BGR_YUYV);
+    cv::cvtColor(image_color_mat, bgr_image, cv::COLOR_YUV2BGR_YUYV);
     std::stringstream name;
     name << "capture-" << aos::realtime_clock::now() << ".png";
-    cv::imwrite(name.str(), rgb_image);
+    cv::imwrite(name.str(), bgr_image);
     LOG(INFO) << "Saved image file: " << name.str();
   } else if ((keystroke & 0xFF) == static_cast<int>('q')) {
     return false;
diff --git a/y2022/wpilib_interface.cc b/y2022/wpilib_interface.cc
index 9586c25..32482ea 100644
--- a/y2022/wpilib_interface.cc
+++ b/y2022/wpilib_interface.cc
@@ -68,14 +68,6 @@
 // DMA stuff and then removing the * 2.0 in *_translate.
 // The low bit is direction.
 
-double drivetrain_translate(int32_t in) {
-  return ((static_cast<double>(in) /
-           Values::kDrivetrainEncoderCountsPerRevolution()) *
-          (2.0 * M_PI)) *
-         Values::kDrivetrainEncoderRatio() *
-         control_loops::drivetrain::kWheelRadius;
-}
-
 double drivetrain_velocity_translate(double in) {
   return (((1.0 / in) / Values::kDrivetrainCyclesPerRevolution()) *
           (2.0 * M_PI)) *
@@ -127,12 +119,14 @@
       frc971::control_loops::drivetrain::Position::Builder drivetrain_builder =
           builder.MakeBuilder<frc971::control_loops::drivetrain::Position>();
       drivetrain_builder.add_left_encoder(
-          drivetrain_translate(drivetrain_left_encoder_->GetRaw()));
+          constants::Values::DrivetrainEncoderToMeters(
+              drivetrain_left_encoder_->GetRaw()));
       drivetrain_builder.add_left_speed(
           drivetrain_velocity_translate(drivetrain_left_encoder_->GetPeriod()));
 
       drivetrain_builder.add_right_encoder(
-          -drivetrain_translate(drivetrain_right_encoder_->GetRaw()));
+          -constants::Values::DrivetrainEncoderToMeters(
+              drivetrain_right_encoder_->GetRaw()));
       drivetrain_builder.add_right_speed(-drivetrain_velocity_translate(
           drivetrain_right_encoder_->GetPeriod()));
 
diff --git a/y2022/y2022.json b/y2022/y2022.json
index 010c675..4fafa8e 100644
--- a/y2022/y2022.json
+++ b/y2022/y2022.json
@@ -18,6 +18,7 @@
     "y2022_pi3.json",
     "y2022_pi4.json",
     "y2022_pi5.json",
+    "y2022_imu.json",
     "y2022_logger.json"
   ]
 }
diff --git a/y2022/y2022_imu.json b/y2022/y2022_imu.json
new file mode 100644
index 0000000..9478123
--- /dev/null
+++ b/y2022/y2022_imu.json
@@ -0,0 +1,376 @@
+{
+  "channels": [
+    {
+      "name": "/imu/aos",
+      "type": "aos.timing.Report",
+      "source_node": "imu",
+      "frequency": 50,
+      "num_senders": 20,
+      "max_size": 4096
+    },
+    {
+      "name": "/imu/aos",
+      "type": "aos.logging.LogMessageFbs",
+      "source_node": "imu",
+      "frequency": 200,
+      "num_senders": 20
+    },
+    {
+      "name": "/imu/aos",
+      "type": "aos.starter.Status",
+      "source_node": "imu",
+      "frequency": 50,
+      "num_senders": 20,
+      "destination_nodes": [
+        {
+          "name": "roborio",
+          "priority": 5,
+          "time_to_live": 5000000
+        },
+        {
+          "name": "logger",
+          "priority": 5,
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/imu/aos",
+      "type": "aos.starter.StarterRpc",
+      "source_node": "imu",
+      "frequency": 10,
+      "num_senders": 2,
+      "destination_nodes": [
+        {
+          "name": "roborio",
+          "priority": 5,
+          "time_to_live": 5000000
+        },
+        {
+          "name": "logger",
+          "priority": 5,
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "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": 10,
+      "num_senders": 2
+    },
+    {
+      "name": "/imu/aos",
+      "type": "aos.message_bridge.Timestamp",
+      "source_node": "imu",
+      "frequency": 15,
+      "num_senders": 2,
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "roborio",
+        "logger"
+      ],
+      "max_size": 200,
+      "destination_nodes": [
+        {
+          "name": "roborio",
+          "priority": 1,
+          "time_to_live": 5000000
+        },
+        {
+          "name": "logger",
+          "priority": 1,
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/logger/aos",
+      "type": "aos.starter.StarterRpc",
+      "source_node": "logger",
+      "destination_nodes": [
+        {
+          "name": "imu",
+          "priority": 5,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "logger"
+          ],
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/logger/aos/remote_timestamps/imu/logger/aos/aos-starter-StarterRpc",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "logger",
+      "logger": "NOT_LOGGED",
+      "frequency": 20,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
+      "name": "/logger/aos",
+      "type": "aos.starter.Status",
+      "source_node": "logger",
+      "destination_nodes": [
+        {
+          "name": "imu",
+          "priority": 5,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "logger"
+          ],
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/logger/aos/remote_timestamps/imu/logger/aos/aos-starter-Status",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "logger",
+      "logger": "NOT_LOGGED",
+      "frequency": 20,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "aos.starter.StarterRpc",
+      "source_node": "roborio",
+      "destination_nodes": [
+        {
+          "name": "imu",
+          "priority": 5,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "roborio"
+          ],
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/roborio/aos/remote_timestamps/imu/roborio/aos/aos-starter-StarterRpc",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "roborio",
+      "logger": "NOT_LOGGED",
+      "frequency": 20,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
+      "name": "/roborio/aos",
+      "type": "aos.starter.Status",
+      "source_node": "roborio",
+      "destination_nodes": [
+        {
+          "name": "imu",
+          "priority": 5,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "roborio"
+          ],
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/roborio/aos/remote_timestamps/imu/roborio/aos/aos-starter-Status",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "roborio",
+      "logger": "NOT_LOGGED",
+      "frequency": 20,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
+      "name": "/localizer",
+      "type": "frc971.controls.LocalizerStatus",
+      "source_node": "imu",
+      "frequency": 2200,
+      "max_size": 2000,
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "roborio"
+      ],
+      "destination_nodes": [
+        {
+          "name": "logger",
+          "priority": 5,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "imu"
+          ],
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/imu/aos/remote_timestamps/logger/localizer/frc971-controls-LocalizerStatus",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "imu",
+      "logger": "NOT_LOGGED",
+      "frequency": 2200,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
+      "name": "/localizer",
+      "type": "frc971.controls.LocalizerOutput",
+      "source_node": "imu",
+      "frequency": 200,
+      "max_size": 200,
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "roborio"
+      ],
+      "destination_nodes": [
+        {
+          "name": "roborio",
+          "priority": 5,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "imu"
+          ],
+          "time_to_live": 5000000
+        },
+        {
+          "name": "logger",
+          "priority": 5,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "imu"
+          ],
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/imu/aos/remote_timestamps/roborio/localizer/frc971-controls-LocalizerOutput",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "imu",
+      "logger": "NOT_LOGGED",
+      "frequency": 200,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
+      "name": "/imu/aos/remote_timestamps/logger/localizer/frc971-controls-LocalizerOutput",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "imu",
+      "logger": "NOT_LOGGED",
+      "frequency": 200,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
+      "name": "/localizer",
+      "type": "frc971.IMUValuesBatch",
+      "source_node": "imu",
+      "frequency": 2200,
+      "max_size": 1600,
+      "num_senders": 2,
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "logger"
+      ],
+      "destination_nodes": [
+        {
+          "name": "logger",
+          "priority": 5,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "imu"
+          ],
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/imu/aos/remote_timestamps/logger/localizer/frc971-IMUValuesBatch",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "imu",
+      "logger": "NOT_LOGGED",
+      "frequency": 2200,
+      "num_senders": 2,
+      "max_size": 200
+    }
+  ],
+  "applications": [
+    {
+      "name": "message_bridge_client",
+      "executable_name": "message_bridge_client",
+      "nodes": [
+        "imu"
+      ]
+    },
+    {
+      "name": "localizer",
+      "executable_name": "localizer",
+      "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": [
+        "logger"
+      ]
+    },
+    {
+      "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-7",
+        "pi-7971-7",
+        "pi-8971-7",
+        "pi-9971-7"
+      ],
+      "port": 9971
+    },
+    {
+      "name": "logger"
+    },
+    {
+      "name": "roborio"
+    }
+  ]
+}
diff --git a/y2022/y2022_logger.json b/y2022/y2022_logger.json
index 1c71234..592109e 100644
--- a/y2022/y2022_logger.json
+++ b/y2022/y2022_logger.json
@@ -20,22 +20,6 @@
    },
     {
       "name": "/drivetrain",
-      "type": "frc971.IMUValuesBatch",
-      "source_node": "roborio",
-      "logger": "LOCAL_AND_REMOTE_LOGGER",
-      "logger_nodes": [
-        "logger"
-      ],
-      "destination_nodes": [
-        {
-          "name": "logger",
-          "priority": 2,
-          "time_to_live": 500000000
-        }
-      ]
-    },
-    {
-      "name": "/drivetrain",
       "type": "frc971.control_loops.drivetrain.Position",
       "source_node": "roborio",
       "logger": "LOCAL_AND_REMOTE_LOGGER",
@@ -268,6 +252,15 @@
           ]
         },
         {
+          "name": "imu",
+          "priority": 1,
+          "time_to_live": 5000000,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "logger"
+          ]
+        },
+        {
           "name": "roborio",
           "priority": 1,
           "time_to_live": 5000000,
@@ -288,6 +281,15 @@
       "max_size": 200
     },
     {
+      "name": "/logger/aos/remote_timestamps/imu/logger/aos/aos-message_bridge-Timestamp",
+      "type": "aos.message_bridge.RemoteMessage",
+      "source_node": "logger",
+      "logger": "NOT_LOGGED",
+      "frequency": 20,
+      "num_senders": 2,
+      "max_size": 200
+    },
+    {
       "name": "/logger/aos/remote_timestamps/pi1/logger/aos/aos-message_bridge-Timestamp",
       "type": "aos.message_bridge.RemoteMessage",
       "source_node": "logger",
@@ -474,6 +476,9 @@
       "name": "roborio"
     },
     {
+      "name": "imu"
+    },
+    {
       "name": "pi4"
     },
     {
diff --git a/y2022/y2022_pi_template.json b/y2022/y2022_pi_template.json
index 823a7f5..07835a0 100644
--- a/y2022/y2022_pi_template.json
+++ b/y2022/y2022_pi_template.json
@@ -110,7 +110,8 @@
       "type": "y2022.vision.TargetEstimate",
       "source_node": "pi{{ NUM }}",
       "frequency": 25,
-      "num_senders": 2
+      "num_senders": 2,
+      "max_size": 20000
     },
     {
       "name": "/logger/aos",
diff --git a/y2022/y2022_roborio.json b/y2022/y2022_roborio.json
index 24144a8..cb1b2d8 100644
--- a/y2022/y2022_roborio.json
+++ b/y2022/y2022_roborio.json
@@ -138,12 +138,19 @@
       "max_size": 208
     },
     {
+      "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": 304,
+      "max_size": 512,
       "destination_nodes": [
         {
           "name": "pi1",
@@ -189,6 +196,15 @@
             "roborio"
           ],
           "time_to_live": 5000000
+        },
+        {
+          "name": "imu",
+          "priority": 1,
+          "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+          "timestamp_logger_nodes": [
+            "roborio"
+          ],
+          "time_to_live": 5000000
         }
       ]
     },
@@ -204,7 +220,18 @@
       "type": "y2022.control_loops.superstructure.Status",
       "source_node": "roborio",
       "frequency": 200,
-      "num_senders": 2
+      "num_senders": 2,
+      "logger": "LOCAL_AND_REMOTE_LOGGER",
+      "logger_nodes": [
+        "imu"
+      ],
+      "destination_nodes": [
+        {
+          "name": "imu",
+          "priority": 5,
+          "time_to_live": 5000000
+        }
+      ]
     },
     {
       "name": "/superstructure",
@@ -224,14 +251,6 @@
     },
     {
       "name": "/drivetrain",
-      "type": "frc971.IMUValuesBatch",
-      "source_node": "roborio",
-      "frequency": 250,
-      "max_size": 2000,
-      "num_senders": 2
-    },
-    {
-      "name": "/drivetrain",
       "type": "frc971.sensors.GyroReading",
       "source_node": "roborio",
       "frequency": 200,
@@ -282,7 +301,31 @@
       "source_node": "roborio",
       "frequency": 200,
       "max_size": 80,
-      "num_senders": 2
+      "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": 200,
+      "num_senders": 2,
+      "max_size": 200
     },
     {
       "name": "/drivetrain",
@@ -297,7 +340,31 @@
       "type": "frc971.control_loops.drivetrain.LocalizerControl",
       "source_node": "roborio",
       "frequency": 200,
-      "max_size": 96
+      "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": 200,
+      "num_senders": 2,
+      "max_size": 200
     },
     {
       "name": "/drivetrain",
@@ -435,6 +502,9 @@
       "port": 9971
     },
     {
+      "name": "imu"
+    },
+    {
       "name": "logger"
     },
     {
diff --git a/yarn.lock b/yarn.lock
index 7c4ac25..207757e 100644
--- a/yarn.lock
+++ b/yarn.lock
@@ -133,7 +133,7 @@
   dependencies:
     "@babel/highlight" "^7.16.7"
 
-"@babel/compat-data@^7.13.11", "@babel/compat-data@^7.16.4", "@babel/compat-data@^7.16.8":
+"@babel/compat-data@^7.16.4":
   version "7.16.8"
   resolved "https://registry.yarnpkg.com/@babel/compat-data/-/compat-data-7.16.8.tgz#31560f9f29fdf1868de8cb55049538a1b9732a60"
   integrity sha512-m7OkX0IdKLKPpBlJtF561YJal5y/jyI5fNfWbPxh2D/nbzzGI4qRyrD8xO2jB24u7l+5I2a43scCG2IrfjC50Q==
@@ -189,22 +189,7 @@
     jsesc "^2.5.1"
     source-map "^0.5.0"
 
-"@babel/helper-annotate-as-pure@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/helper-annotate-as-pure/-/helper-annotate-as-pure-7.16.7.tgz#bb2339a7534a9c128e3102024c60760a3a7f3862"
-  integrity sha512-s6t2w/IPQVTAET1HitoowRGXooX8mCgtuP5195wD/QJPV6wYjpujCGF7JuMODVX2ZAJOf1GT6DT9MHEZvLOFSw==
-  dependencies:
-    "@babel/types" "^7.16.7"
-
-"@babel/helper-builder-binary-assignment-operator-visitor@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/helper-builder-binary-assignment-operator-visitor/-/helper-builder-binary-assignment-operator-visitor-7.16.7.tgz#38d138561ea207f0f69eb1626a418e4f7e6a580b"
-  integrity sha512-C6FdbRaxYjwVu/geKW4ZeQ0Q31AftgRcdSnZ5/jsH6BzCJbtvXvhpfkbkThYSuutZA7nCXpPR6AD9zd1dprMkA==
-  dependencies:
-    "@babel/helper-explode-assignable-expression" "^7.16.7"
-    "@babel/types" "^7.16.7"
-
-"@babel/helper-compilation-targets@^7.13.0", "@babel/helper-compilation-targets@^7.16.7":
+"@babel/helper-compilation-targets@^7.16.7":
   version "7.16.7"
   resolved "https://registry.yarnpkg.com/@babel/helper-compilation-targets/-/helper-compilation-targets-7.16.7.tgz#06e66c5f299601e6c7da350049315e83209d551b"
   integrity sha512-mGojBwIWcwGD6rfqgRXVlVYmPAv7eOpIemUG3dGnDdCY4Pae70ROij3XmfrH6Fa1h1aiDylpglbZyktfzyo/hA==
@@ -214,41 +199,6 @@
     browserslist "^4.17.5"
     semver "^6.3.0"
 
-"@babel/helper-create-class-features-plugin@^7.16.7":
-  version "7.16.10"
-  resolved "https://registry.yarnpkg.com/@babel/helper-create-class-features-plugin/-/helper-create-class-features-plugin-7.16.10.tgz#8a6959b9cc818a88815ba3c5474619e9c0f2c21c"
-  integrity sha512-wDeej0pu3WN/ffTxMNCPW5UCiOav8IcLRxSIyp/9+IF2xJUM9h/OYjg0IJLHaL6F8oU8kqMz9nc1vryXhMsgXg==
-  dependencies:
-    "@babel/helper-annotate-as-pure" "^7.16.7"
-    "@babel/helper-environment-visitor" "^7.16.7"
-    "@babel/helper-function-name" "^7.16.7"
-    "@babel/helper-member-expression-to-functions" "^7.16.7"
-    "@babel/helper-optimise-call-expression" "^7.16.7"
-    "@babel/helper-replace-supers" "^7.16.7"
-    "@babel/helper-split-export-declaration" "^7.16.7"
-
-"@babel/helper-create-regexp-features-plugin@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/helper-create-regexp-features-plugin/-/helper-create-regexp-features-plugin-7.16.7.tgz#0cb82b9bac358eb73bfbd73985a776bfa6b14d48"
-  integrity sha512-fk5A6ymfp+O5+p2yCkXAu5Kyj6v0xh0RBeNcAkYUMDvvAAoxvSKXn+Jb37t/yWFiQVDFK1ELpUTD8/aLhCPu+g==
-  dependencies:
-    "@babel/helper-annotate-as-pure" "^7.16.7"
-    regexpu-core "^4.7.1"
-
-"@babel/helper-define-polyfill-provider@^0.3.1":
-  version "0.3.1"
-  resolved "https://registry.yarnpkg.com/@babel/helper-define-polyfill-provider/-/helper-define-polyfill-provider-0.3.1.tgz#52411b445bdb2e676869e5a74960d2d3826d2665"
-  integrity sha512-J9hGMpJQmtWmj46B3kBHmL38UhJGhYX7eqkcq+2gsstyYt341HmPeWspihX43yVRA0mS+8GGk2Gckc7bY/HCmA==
-  dependencies:
-    "@babel/helper-compilation-targets" "^7.13.0"
-    "@babel/helper-module-imports" "^7.12.13"
-    "@babel/helper-plugin-utils" "^7.13.0"
-    "@babel/traverse" "^7.13.0"
-    debug "^4.1.1"
-    lodash.debounce "^4.0.8"
-    resolve "^1.14.2"
-    semver "^6.1.2"
-
 "@babel/helper-environment-visitor@^7.16.7":
   version "7.16.7"
   resolved "https://registry.yarnpkg.com/@babel/helper-environment-visitor/-/helper-environment-visitor-7.16.7.tgz#ff484094a839bde9d89cd63cba017d7aae80ecd7"
@@ -256,13 +206,6 @@
   dependencies:
     "@babel/types" "^7.16.7"
 
-"@babel/helper-explode-assignable-expression@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/helper-explode-assignable-expression/-/helper-explode-assignable-expression-7.16.7.tgz#12a6d8522fdd834f194e868af6354e8650242b7a"
-  integrity sha512-KyUenhWMC8VrxzkGP0Jizjo4/Zx+1nNZhgocs+gLzyZyB8SHidhoq9KK/8Ato4anhwsivfkBLftky7gvzbZMtQ==
-  dependencies:
-    "@babel/types" "^7.16.7"
-
 "@babel/helper-function-name@^7.16.7":
   version "7.16.7"
   resolved "https://registry.yarnpkg.com/@babel/helper-function-name/-/helper-function-name-7.16.7.tgz#f1ec51551fb1c8956bc8dd95f38523b6cf375f8f"
@@ -286,14 +229,7 @@
   dependencies:
     "@babel/types" "^7.16.7"
 
-"@babel/helper-member-expression-to-functions@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/helper-member-expression-to-functions/-/helper-member-expression-to-functions-7.16.7.tgz#42b9ca4b2b200123c3b7e726b0ae5153924905b0"
-  integrity sha512-VtJ/65tYiU/6AbMTDwyoXGPKHgTsfRarivm+YbB5uAzKUyuPjgZSgAFeG87FCigc7KNHu2Pegh1XIT3lXjvz3Q==
-  dependencies:
-    "@babel/types" "^7.16.7"
-
-"@babel/helper-module-imports@^7.12.13", "@babel/helper-module-imports@^7.16.7":
+"@babel/helper-module-imports@^7.16.7":
   version "7.16.7"
   resolved "https://registry.yarnpkg.com/@babel/helper-module-imports/-/helper-module-imports-7.16.7.tgz#25612a8091a999704461c8a222d0efec5d091437"
   integrity sha512-LVtS6TqjJHFc+nYeITRo6VLXve70xmq7wPhWTqDJusJEgGmkAACWwMiTNrvfoQo6hEhFwAIixNkvB0jPXDL8Wg==
@@ -314,38 +250,6 @@
     "@babel/traverse" "^7.16.7"
     "@babel/types" "^7.16.7"
 
-"@babel/helper-optimise-call-expression@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/helper-optimise-call-expression/-/helper-optimise-call-expression-7.16.7.tgz#a34e3560605abbd31a18546bd2aad3e6d9a174f2"
-  integrity sha512-EtgBhg7rd/JcnpZFXpBy0ze1YRfdm7BnBX4uKMBd3ixa3RGAE002JZB66FJyNH7g0F38U05pXmA5P8cBh7z+1w==
-  dependencies:
-    "@babel/types" "^7.16.7"
-
-"@babel/helper-plugin-utils@^7.0.0", "@babel/helper-plugin-utils@^7.10.4", "@babel/helper-plugin-utils@^7.12.13", "@babel/helper-plugin-utils@^7.13.0", "@babel/helper-plugin-utils@^7.14.5", "@babel/helper-plugin-utils@^7.16.7", "@babel/helper-plugin-utils@^7.8.0", "@babel/helper-plugin-utils@^7.8.3":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/helper-plugin-utils/-/helper-plugin-utils-7.16.7.tgz#aa3a8ab4c3cceff8e65eb9e73d87dc4ff320b2f5"
-  integrity sha512-Qg3Nk7ZxpgMrsox6HreY1ZNKdBq7K72tDSliA6dCl5f007jR4ne8iD5UzuNnCJH2xBf2BEEVGr+/OL6Gdp7RxA==
-
-"@babel/helper-remap-async-to-generator@^7.16.8":
-  version "7.16.8"
-  resolved "https://registry.yarnpkg.com/@babel/helper-remap-async-to-generator/-/helper-remap-async-to-generator-7.16.8.tgz#29ffaade68a367e2ed09c90901986918d25e57e3"
-  integrity sha512-fm0gH7Flb8H51LqJHy3HJ3wnE1+qtYR2A99K06ahwrawLdOFsCEWjZOrYricXJHoPSudNKxrMBUPEIPxiIIvBw==
-  dependencies:
-    "@babel/helper-annotate-as-pure" "^7.16.7"
-    "@babel/helper-wrap-function" "^7.16.8"
-    "@babel/types" "^7.16.8"
-
-"@babel/helper-replace-supers@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/helper-replace-supers/-/helper-replace-supers-7.16.7.tgz#e9f5f5f32ac90429c1a4bdec0f231ef0c2838ab1"
-  integrity sha512-y9vsWilTNaVnVh6xiJfABzsNpgDPKev9HnAgz6Gb1p6UUwf9NepdlsV7VXGCftJM+jqD5f7JIEubcpLjZj5dBw==
-  dependencies:
-    "@babel/helper-environment-visitor" "^7.16.7"
-    "@babel/helper-member-expression-to-functions" "^7.16.7"
-    "@babel/helper-optimise-call-expression" "^7.16.7"
-    "@babel/traverse" "^7.16.7"
-    "@babel/types" "^7.16.7"
-
 "@babel/helper-simple-access@^7.16.7":
   version "7.16.7"
   resolved "https://registry.yarnpkg.com/@babel/helper-simple-access/-/helper-simple-access-7.16.7.tgz#d656654b9ea08dbb9659b69d61063ccd343ff0f7"
@@ -353,13 +257,6 @@
   dependencies:
     "@babel/types" "^7.16.7"
 
-"@babel/helper-skip-transparent-expression-wrappers@^7.16.0":
-  version "7.16.0"
-  resolved "https://registry.yarnpkg.com/@babel/helper-skip-transparent-expression-wrappers/-/helper-skip-transparent-expression-wrappers-7.16.0.tgz#0ee3388070147c3ae051e487eca3ebb0e2e8bb09"
-  integrity sha512-+il1gTy0oHwUsBQZyJvukbB4vPMdcYBrFHa0Uc4AizLxbq6BOYC51Rv4tWocX9BLBDLZ4kc6qUFpQ6HRgL+3zw==
-  dependencies:
-    "@babel/types" "^7.16.0"
-
 "@babel/helper-split-export-declaration@^7.16.7":
   version "7.16.7"
   resolved "https://registry.yarnpkg.com/@babel/helper-split-export-declaration/-/helper-split-export-declaration-7.16.7.tgz#0b648c0c42da9d3920d85ad585f2778620b8726b"
@@ -377,16 +274,6 @@
   resolved "https://registry.yarnpkg.com/@babel/helper-validator-option/-/helper-validator-option-7.16.7.tgz#b203ce62ce5fe153899b617c08957de860de4d23"
   integrity sha512-TRtenOuRUVo9oIQGPC5G9DgK4743cdxvtOw0weQNpZXaS16SCBi5MNjZF8vba3ETURjZpTbVn7Vvcf2eAwFozQ==
 
-"@babel/helper-wrap-function@^7.16.8":
-  version "7.16.8"
-  resolved "https://registry.yarnpkg.com/@babel/helper-wrap-function/-/helper-wrap-function-7.16.8.tgz#58afda087c4cd235de92f7ceedebca2c41274200"
-  integrity sha512-8RpyRVIAW1RcDDGTA+GpPAwV22wXCfKOoM9bet6TLkGIFTkRQSkH1nMQ5Yet4MpoXe1ZwHPVtNasc2w0uZMqnw==
-  dependencies:
-    "@babel/helper-function-name" "^7.16.7"
-    "@babel/template" "^7.16.7"
-    "@babel/traverse" "^7.16.8"
-    "@babel/types" "^7.16.8"
-
 "@babel/helpers@^7.16.7":
   version "7.16.7"
   resolved "https://registry.yarnpkg.com/@babel/helpers/-/helpers-7.16.7.tgz#7e3504d708d50344112767c3542fc5e357fffefc"
@@ -415,596 +302,6 @@
   resolved "https://registry.yarnpkg.com/@babel/parser/-/parser-7.16.8.tgz#61c243a3875f7d0b0962b0543a33ece6ff2f1f17"
   integrity sha512-i7jDUfrVBWc+7OKcBzEe5n7fbv3i2fWtxKzzCvOjnzSxMfWMigAhtfJ7qzZNGFNMsCCd67+uz553dYKWXPvCKw==
 
-"@babel/plugin-bugfix-safari-id-destructuring-collision-in-function-expression@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-bugfix-safari-id-destructuring-collision-in-function-expression/-/plugin-bugfix-safari-id-destructuring-collision-in-function-expression-7.16.7.tgz#4eda6d6c2a0aa79c70fa7b6da67763dfe2141050"
-  integrity sha512-anv/DObl7waiGEnC24O9zqL0pSuI9hljihqiDuFHC8d7/bjr/4RLGPWuc8rYOff/QPzbEPSkzG8wGG9aDuhHRg==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-bugfix-v8-spread-parameters-in-optional-chaining@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-bugfix-v8-spread-parameters-in-optional-chaining/-/plugin-bugfix-v8-spread-parameters-in-optional-chaining-7.16.7.tgz#cc001234dfc139ac45f6bcf801866198c8c72ff9"
-  integrity sha512-di8vUHRdf+4aJ7ltXhaDbPoszdkh59AQtJM5soLsuHpQJdFQZOA4uGj0V2u/CZ8bJ/u8ULDL5yq6FO/bCXnKHw==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-    "@babel/helper-skip-transparent-expression-wrappers" "^7.16.0"
-    "@babel/plugin-proposal-optional-chaining" "^7.16.7"
-
-"@babel/plugin-proposal-async-generator-functions@^7.16.8":
-  version "7.16.8"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-proposal-async-generator-functions/-/plugin-proposal-async-generator-functions-7.16.8.tgz#3bdd1ebbe620804ea9416706cd67d60787504bc8"
-  integrity sha512-71YHIvMuiuqWJQkebWJtdhQTfd4Q4mF76q2IX37uZPkG9+olBxsX+rH1vkhFto4UeJZ9dPY2s+mDvhDm1u2BGQ==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-    "@babel/helper-remap-async-to-generator" "^7.16.8"
-    "@babel/plugin-syntax-async-generators" "^7.8.4"
-
-"@babel/plugin-proposal-class-properties@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-proposal-class-properties/-/plugin-proposal-class-properties-7.16.7.tgz#925cad7b3b1a2fcea7e59ecc8eb5954f961f91b0"
-  integrity sha512-IobU0Xme31ewjYOShSIqd/ZGM/r/cuOz2z0MDbNrhF5FW+ZVgi0f2lyeoj9KFPDOAqsYxmLWZte1WOwlvY9aww==
-  dependencies:
-    "@babel/helper-create-class-features-plugin" "^7.16.7"
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-proposal-class-static-block@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-proposal-class-static-block/-/plugin-proposal-class-static-block-7.16.7.tgz#712357570b612106ef5426d13dc433ce0f200c2a"
-  integrity sha512-dgqJJrcZoG/4CkMopzhPJjGxsIe9A8RlkQLnL/Vhhx8AA9ZuaRwGSlscSh42hazc7WSrya/IK7mTeoF0DP9tEw==
-  dependencies:
-    "@babel/helper-create-class-features-plugin" "^7.16.7"
-    "@babel/helper-plugin-utils" "^7.16.7"
-    "@babel/plugin-syntax-class-static-block" "^7.14.5"
-
-"@babel/plugin-proposal-dynamic-import@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-proposal-dynamic-import/-/plugin-proposal-dynamic-import-7.16.7.tgz#c19c897eaa46b27634a00fee9fb7d829158704b2"
-  integrity sha512-I8SW9Ho3/8DRSdmDdH3gORdyUuYnk1m4cMxUAdu5oy4n3OfN8flDEH+d60iG7dUfi0KkYwSvoalHzzdRzpWHTg==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-    "@babel/plugin-syntax-dynamic-import" "^7.8.3"
-
-"@babel/plugin-proposal-export-namespace-from@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-proposal-export-namespace-from/-/plugin-proposal-export-namespace-from-7.16.7.tgz#09de09df18445a5786a305681423ae63507a6163"
-  integrity sha512-ZxdtqDXLRGBL64ocZcs7ovt71L3jhC1RGSyR996svrCi3PYqHNkb3SwPJCs8RIzD86s+WPpt2S73+EHCGO+NUA==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-    "@babel/plugin-syntax-export-namespace-from" "^7.8.3"
-
-"@babel/plugin-proposal-json-strings@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-proposal-json-strings/-/plugin-proposal-json-strings-7.16.7.tgz#9732cb1d17d9a2626a08c5be25186c195b6fa6e8"
-  integrity sha512-lNZ3EEggsGY78JavgbHsK9u5P3pQaW7k4axlgFLYkMd7UBsiNahCITShLjNQschPyjtO6dADrL24757IdhBrsQ==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-    "@babel/plugin-syntax-json-strings" "^7.8.3"
-
-"@babel/plugin-proposal-logical-assignment-operators@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-proposal-logical-assignment-operators/-/plugin-proposal-logical-assignment-operators-7.16.7.tgz#be23c0ba74deec1922e639832904be0bea73cdea"
-  integrity sha512-K3XzyZJGQCr00+EtYtrDjmwX7o7PLK6U9bi1nCwkQioRFVUv6dJoxbQjtWVtP+bCPy82bONBKG8NPyQ4+i6yjg==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-    "@babel/plugin-syntax-logical-assignment-operators" "^7.10.4"
-
-"@babel/plugin-proposal-nullish-coalescing-operator@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-proposal-nullish-coalescing-operator/-/plugin-proposal-nullish-coalescing-operator-7.16.7.tgz#141fc20b6857e59459d430c850a0011e36561d99"
-  integrity sha512-aUOrYU3EVtjf62jQrCj63pYZ7k6vns2h/DQvHPWGmsJRYzWXZ6/AsfgpiRy6XiuIDADhJzP2Q9MwSMKauBQ+UQ==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-    "@babel/plugin-syntax-nullish-coalescing-operator" "^7.8.3"
-
-"@babel/plugin-proposal-numeric-separator@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-proposal-numeric-separator/-/plugin-proposal-numeric-separator-7.16.7.tgz#d6b69f4af63fb38b6ca2558442a7fb191236eba9"
-  integrity sha512-vQgPMknOIgiuVqbokToyXbkY/OmmjAzr/0lhSIbG/KmnzXPGwW/AdhdKpi+O4X/VkWiWjnkKOBiqJrTaC98VKw==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-    "@babel/plugin-syntax-numeric-separator" "^7.10.4"
-
-"@babel/plugin-proposal-object-rest-spread@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-proposal-object-rest-spread/-/plugin-proposal-object-rest-spread-7.16.7.tgz#94593ef1ddf37021a25bdcb5754c4a8d534b01d8"
-  integrity sha512-3O0Y4+dw94HA86qSg9IHfyPktgR7q3gpNVAeiKQd+8jBKFaU5NQS1Yatgo4wY+UFNuLjvxcSmzcsHqrhgTyBUA==
-  dependencies:
-    "@babel/compat-data" "^7.16.4"
-    "@babel/helper-compilation-targets" "^7.16.7"
-    "@babel/helper-plugin-utils" "^7.16.7"
-    "@babel/plugin-syntax-object-rest-spread" "^7.8.3"
-    "@babel/plugin-transform-parameters" "^7.16.7"
-
-"@babel/plugin-proposal-optional-catch-binding@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-proposal-optional-catch-binding/-/plugin-proposal-optional-catch-binding-7.16.7.tgz#c623a430674ffc4ab732fd0a0ae7722b67cb74cf"
-  integrity sha512-eMOH/L4OvWSZAE1VkHbr1vckLG1WUcHGJSLqqQwl2GaUqG6QjddvrOaTUMNYiv77H5IKPMZ9U9P7EaHwvAShfA==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-    "@babel/plugin-syntax-optional-catch-binding" "^7.8.3"
-
-"@babel/plugin-proposal-optional-chaining@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-proposal-optional-chaining/-/plugin-proposal-optional-chaining-7.16.7.tgz#7cd629564724816c0e8a969535551f943c64c39a"
-  integrity sha512-eC3xy+ZrUcBtP7x+sq62Q/HYd674pPTb/77XZMb5wbDPGWIdUbSr4Agr052+zaUPSb+gGRnjxXfKFvx5iMJ+DA==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-    "@babel/helper-skip-transparent-expression-wrappers" "^7.16.0"
-    "@babel/plugin-syntax-optional-chaining" "^7.8.3"
-
-"@babel/plugin-proposal-private-methods@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-proposal-private-methods/-/plugin-proposal-private-methods-7.16.7.tgz#e418e3aa6f86edd6d327ce84eff188e479f571e0"
-  integrity sha512-7twV3pzhrRxSwHeIvFE6coPgvo+exNDOiGUMg39o2LiLo1Y+4aKpfkcLGcg1UHonzorCt7SNXnoMyCnnIOA8Sw==
-  dependencies:
-    "@babel/helper-create-class-features-plugin" "^7.16.7"
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-proposal-private-property-in-object@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-proposal-private-property-in-object/-/plugin-proposal-private-property-in-object-7.16.7.tgz#b0b8cef543c2c3d57e59e2c611994861d46a3fce"
-  integrity sha512-rMQkjcOFbm+ufe3bTZLyOfsOUOxyvLXZJCTARhJr+8UMSoZmqTe1K1BgkFcrW37rAchWg57yI69ORxiWvUINuQ==
-  dependencies:
-    "@babel/helper-annotate-as-pure" "^7.16.7"
-    "@babel/helper-create-class-features-plugin" "^7.16.7"
-    "@babel/helper-plugin-utils" "^7.16.7"
-    "@babel/plugin-syntax-private-property-in-object" "^7.14.5"
-
-"@babel/plugin-proposal-unicode-property-regex@^7.16.7", "@babel/plugin-proposal-unicode-property-regex@^7.4.4":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-proposal-unicode-property-regex/-/plugin-proposal-unicode-property-regex-7.16.7.tgz#635d18eb10c6214210ffc5ff4932552de08188a2"
-  integrity sha512-QRK0YI/40VLhNVGIjRNAAQkEHws0cswSdFFjpFyt943YmJIU1da9uW63Iu6NFV6CxTZW5eTDCrwZUstBWgp/Rg==
-  dependencies:
-    "@babel/helper-create-regexp-features-plugin" "^7.16.7"
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-syntax-async-generators@^7.8.4":
-  version "7.8.4"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-syntax-async-generators/-/plugin-syntax-async-generators-7.8.4.tgz#a983fb1aeb2ec3f6ed042a210f640e90e786fe0d"
-  integrity sha512-tycmZxkGfZaxhMRbXlPXuVFpdWlXpir2W4AMhSJgRKzk/eDlIXOhb2LHWoLpDF7TEHylV5zNhykX6KAgHJmTNw==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.8.0"
-
-"@babel/plugin-syntax-class-properties@^7.12.13":
-  version "7.12.13"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-syntax-class-properties/-/plugin-syntax-class-properties-7.12.13.tgz#b5c987274c4a3a82b89714796931a6b53544ae10"
-  integrity sha512-fm4idjKla0YahUNgFNLCB0qySdsoPiZP3iQE3rky0mBUtMZ23yDJ9SJdg6dXTSDnulOVqiF3Hgr9nbXvXTQZYA==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.12.13"
-
-"@babel/plugin-syntax-class-static-block@^7.14.5":
-  version "7.14.5"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-syntax-class-static-block/-/plugin-syntax-class-static-block-7.14.5.tgz#195df89b146b4b78b3bf897fd7a257c84659d406"
-  integrity sha512-b+YyPmr6ldyNnM6sqYeMWE+bgJcJpO6yS4QD7ymxgH34GBPNDM/THBh8iunyvKIZztiwLH4CJZ0RxTk9emgpjw==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.14.5"
-
-"@babel/plugin-syntax-dynamic-import@^7.8.3":
-  version "7.8.3"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-syntax-dynamic-import/-/plugin-syntax-dynamic-import-7.8.3.tgz#62bf98b2da3cd21d626154fc96ee5b3cb68eacb3"
-  integrity sha512-5gdGbFon+PszYzqs83S3E5mpi7/y/8M9eC90MRTZfduQOYW76ig6SOSPNe41IG5LoP3FGBn2N0RjVDSQiS94kQ==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.8.0"
-
-"@babel/plugin-syntax-export-namespace-from@^7.8.3":
-  version "7.8.3"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-syntax-export-namespace-from/-/plugin-syntax-export-namespace-from-7.8.3.tgz#028964a9ba80dbc094c915c487ad7c4e7a66465a"
-  integrity sha512-MXf5laXo6c1IbEbegDmzGPwGNTsHZmEy6QGznu5Sh2UCWvueywb2ee+CCE4zQiZstxU9BMoQO9i6zUFSY0Kj0Q==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.8.3"
-
-"@babel/plugin-syntax-json-strings@^7.8.3":
-  version "7.8.3"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-syntax-json-strings/-/plugin-syntax-json-strings-7.8.3.tgz#01ca21b668cd8218c9e640cb6dd88c5412b2c96a"
-  integrity sha512-lY6kdGpWHvjoe2vk4WrAapEuBR69EMxZl+RoGRhrFGNYVK8mOPAW8VfbT/ZgrFbXlDNiiaxQnAtgVCZ6jv30EA==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.8.0"
-
-"@babel/plugin-syntax-logical-assignment-operators@^7.10.4":
-  version "7.10.4"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-syntax-logical-assignment-operators/-/plugin-syntax-logical-assignment-operators-7.10.4.tgz#ca91ef46303530448b906652bac2e9fe9941f699"
-  integrity sha512-d8waShlpFDinQ5MtvGU9xDAOzKH47+FFoney2baFIoMr952hKOLp1HR7VszoZvOsV/4+RRszNY7D17ba0te0ig==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.10.4"
-
-"@babel/plugin-syntax-nullish-coalescing-operator@^7.8.3":
-  version "7.8.3"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-syntax-nullish-coalescing-operator/-/plugin-syntax-nullish-coalescing-operator-7.8.3.tgz#167ed70368886081f74b5c36c65a88c03b66d1a9"
-  integrity sha512-aSff4zPII1u2QD7y+F8oDsz19ew4IGEJg9SVW+bqwpwtfFleiQDMdzA/R+UlWDzfnHFCxxleFT0PMIrR36XLNQ==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.8.0"
-
-"@babel/plugin-syntax-numeric-separator@^7.10.4":
-  version "7.10.4"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-syntax-numeric-separator/-/plugin-syntax-numeric-separator-7.10.4.tgz#b9b070b3e33570cd9fd07ba7fa91c0dd37b9af97"
-  integrity sha512-9H6YdfkcK/uOnY/K7/aA2xpzaAgkQn37yzWUMRK7OaPOqOpGS1+n0H5hxT9AUw9EsSjPW8SVyMJwYRtWs3X3ug==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.10.4"
-
-"@babel/plugin-syntax-object-rest-spread@^7.8.3":
-  version "7.8.3"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-syntax-object-rest-spread/-/plugin-syntax-object-rest-spread-7.8.3.tgz#60e225edcbd98a640332a2e72dd3e66f1af55871"
-  integrity sha512-XoqMijGZb9y3y2XskN+P1wUGiVwWZ5JmoDRwx5+3GmEplNyVM2s2Dg8ILFQm8rWM48orGy5YpI5Bl8U1y7ydlA==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.8.0"
-
-"@babel/plugin-syntax-optional-catch-binding@^7.8.3":
-  version "7.8.3"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-syntax-optional-catch-binding/-/plugin-syntax-optional-catch-binding-7.8.3.tgz#6111a265bcfb020eb9efd0fdfd7d26402b9ed6c1"
-  integrity sha512-6VPD0Pc1lpTqw0aKoeRTMiB+kWhAoT24PA+ksWSBrFtl5SIRVpZlwN3NNPQjehA2E/91FV3RjLWoVTglWcSV3Q==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.8.0"
-
-"@babel/plugin-syntax-optional-chaining@^7.8.3":
-  version "7.8.3"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-syntax-optional-chaining/-/plugin-syntax-optional-chaining-7.8.3.tgz#4f69c2ab95167e0180cd5336613f8c5788f7d48a"
-  integrity sha512-KoK9ErH1MBlCPxV0VANkXW2/dw4vlbGDrFgz8bmUsBGYkFRcbRwMh6cIJubdPrkxRwuGdtCk0v/wPTKbQgBjkg==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.8.0"
-
-"@babel/plugin-syntax-private-property-in-object@^7.14.5":
-  version "7.14.5"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-syntax-private-property-in-object/-/plugin-syntax-private-property-in-object-7.14.5.tgz#0dc6671ec0ea22b6e94a1114f857970cd39de1ad"
-  integrity sha512-0wVnp9dxJ72ZUJDV27ZfbSj6iHLoytYZmh3rFcxNnvsJF3ktkzLDZPy/mA17HGsaQT3/DQsWYX1f1QGWkCoVUg==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.14.5"
-
-"@babel/plugin-syntax-top-level-await@^7.14.5":
-  version "7.14.5"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-syntax-top-level-await/-/plugin-syntax-top-level-await-7.14.5.tgz#c1cfdadc35a646240001f06138247b741c34d94c"
-  integrity sha512-hx++upLv5U1rgYfwe1xBQUhRmU41NEvpUvrp8jkrSCdvGSnM5/qdRMtylJ6PG5OFkBaHkbTAKTnd3/YyESRHFw==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.14.5"
-
-"@babel/plugin-transform-arrow-functions@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-arrow-functions/-/plugin-transform-arrow-functions-7.16.7.tgz#44125e653d94b98db76369de9c396dc14bef4154"
-  integrity sha512-9ffkFFMbvzTvv+7dTp/66xvZAWASuPD5Tl9LK3Z9vhOmANo6j94rik+5YMBt4CwHVMWLWpMsriIc2zsa3WW3xQ==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-async-to-generator@^7.16.8":
-  version "7.16.8"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-async-to-generator/-/plugin-transform-async-to-generator-7.16.8.tgz#b83dff4b970cf41f1b819f8b49cc0cfbaa53a808"
-  integrity sha512-MtmUmTJQHCnyJVrScNzNlofQJ3dLFuobYn3mwOTKHnSCMtbNsqvF71GQmJfFjdrXSsAA7iysFmYWw4bXZ20hOg==
-  dependencies:
-    "@babel/helper-module-imports" "^7.16.7"
-    "@babel/helper-plugin-utils" "^7.16.7"
-    "@babel/helper-remap-async-to-generator" "^7.16.8"
-
-"@babel/plugin-transform-block-scoped-functions@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-block-scoped-functions/-/plugin-transform-block-scoped-functions-7.16.7.tgz#4d0d57d9632ef6062cdf354bb717102ee042a620"
-  integrity sha512-JUuzlzmF40Z9cXyytcbZEZKckgrQzChbQJw/5PuEHYeqzCsvebDx0K0jWnIIVcmmDOAVctCgnYs0pMcrYj2zJg==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-block-scoping@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-block-scoping/-/plugin-transform-block-scoping-7.16.7.tgz#f50664ab99ddeaee5bc681b8f3a6ea9d72ab4f87"
-  integrity sha512-ObZev2nxVAYA4bhyusELdo9hb3H+A56bxH3FZMbEImZFiEDYVHXQSJ1hQKFlDnlt8G9bBrCZ5ZpURZUrV4G5qQ==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-classes@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-classes/-/plugin-transform-classes-7.16.7.tgz#8f4b9562850cd973de3b498f1218796eb181ce00"
-  integrity sha512-WY7og38SFAGYRe64BrjKf8OrE6ulEHtr5jEYaZMwox9KebgqPi67Zqz8K53EKk1fFEJgm96r32rkKZ3qA2nCWQ==
-  dependencies:
-    "@babel/helper-annotate-as-pure" "^7.16.7"
-    "@babel/helper-environment-visitor" "^7.16.7"
-    "@babel/helper-function-name" "^7.16.7"
-    "@babel/helper-optimise-call-expression" "^7.16.7"
-    "@babel/helper-plugin-utils" "^7.16.7"
-    "@babel/helper-replace-supers" "^7.16.7"
-    "@babel/helper-split-export-declaration" "^7.16.7"
-    globals "^11.1.0"
-
-"@babel/plugin-transform-computed-properties@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-computed-properties/-/plugin-transform-computed-properties-7.16.7.tgz#66dee12e46f61d2aae7a73710f591eb3df616470"
-  integrity sha512-gN72G9bcmenVILj//sv1zLNaPyYcOzUho2lIJBMh/iakJ9ygCo/hEF9cpGb61SCMEDxbbyBoVQxrt+bWKu5KGw==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-destructuring@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-destructuring/-/plugin-transform-destructuring-7.16.7.tgz#ca9588ae2d63978a4c29d3f33282d8603f618e23"
-  integrity sha512-VqAwhTHBnu5xBVDCvrvqJbtLUa++qZaWC0Fgr2mqokBlulZARGyIvZDoqbPlPaKImQ9dKAcCzbv+ul//uqu70A==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-dotall-regex@^7.16.7", "@babel/plugin-transform-dotall-regex@^7.4.4":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-dotall-regex/-/plugin-transform-dotall-regex-7.16.7.tgz#6b2d67686fab15fb6a7fd4bd895d5982cfc81241"
-  integrity sha512-Lyttaao2SjZF6Pf4vk1dVKv8YypMpomAbygW+mU5cYP3S5cWTfCJjG8xV6CFdzGFlfWK81IjL9viiTvpb6G7gQ==
-  dependencies:
-    "@babel/helper-create-regexp-features-plugin" "^7.16.7"
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-duplicate-keys@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-duplicate-keys/-/plugin-transform-duplicate-keys-7.16.7.tgz#2207e9ca8f82a0d36a5a67b6536e7ef8b08823c9"
-  integrity sha512-03DvpbRfvWIXyK0/6QiR1KMTWeT6OcQ7tbhjrXyFS02kjuX/mu5Bvnh5SDSWHxyawit2g5aWhKwI86EE7GUnTw==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-exponentiation-operator@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-exponentiation-operator/-/plugin-transform-exponentiation-operator-7.16.7.tgz#efa9862ef97e9e9e5f653f6ddc7b665e8536fe9b"
-  integrity sha512-8UYLSlyLgRixQvlYH3J2ekXFHDFLQutdy7FfFAMm3CPZ6q9wHCwnUyiXpQCe3gVVnQlHc5nsuiEVziteRNTXEA==
-  dependencies:
-    "@babel/helper-builder-binary-assignment-operator-visitor" "^7.16.7"
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-for-of@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-for-of/-/plugin-transform-for-of-7.16.7.tgz#649d639d4617dff502a9a158c479b3b556728d8c"
-  integrity sha512-/QZm9W92Ptpw7sjI9Nx1mbcsWz33+l8kuMIQnDwgQBG5s3fAfQvkRjQ7NqXhtNcKOnPkdICmUHyCaWW06HCsqg==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-function-name@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-function-name/-/plugin-transform-function-name-7.16.7.tgz#5ab34375c64d61d083d7d2f05c38d90b97ec65cf"
-  integrity sha512-SU/C68YVwTRxqWj5kgsbKINakGag0KTgq9f2iZEXdStoAbOzLHEBRYzImmA6yFo8YZhJVflvXmIHUO7GWHmxxA==
-  dependencies:
-    "@babel/helper-compilation-targets" "^7.16.7"
-    "@babel/helper-function-name" "^7.16.7"
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-literals@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-literals/-/plugin-transform-literals-7.16.7.tgz#254c9618c5ff749e87cb0c0cef1a0a050c0bdab1"
-  integrity sha512-6tH8RTpTWI0s2sV6uq3e/C9wPo4PTqqZps4uF0kzQ9/xPLFQtipynvmT1g/dOfEJ+0EQsHhkQ/zyRId8J2b8zQ==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-member-expression-literals@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-member-expression-literals/-/plugin-transform-member-expression-literals-7.16.7.tgz#6e5dcf906ef8a098e630149d14c867dd28f92384"
-  integrity sha512-mBruRMbktKQwbxaJof32LT9KLy2f3gH+27a5XSuXo6h7R3vqltl0PgZ80C8ZMKw98Bf8bqt6BEVi3svOh2PzMw==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-modules-amd@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-modules-amd/-/plugin-transform-modules-amd-7.16.7.tgz#b28d323016a7daaae8609781d1f8c9da42b13186"
-  integrity sha512-KaaEtgBL7FKYwjJ/teH63oAmE3lP34N3kshz8mm4VMAw7U3PxjVwwUmxEFksbgsNUaO3wId9R2AVQYSEGRa2+g==
-  dependencies:
-    "@babel/helper-module-transforms" "^7.16.7"
-    "@babel/helper-plugin-utils" "^7.16.7"
-    babel-plugin-dynamic-import-node "^2.3.3"
-
-"@babel/plugin-transform-modules-commonjs@^7.16.8":
-  version "7.16.8"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-modules-commonjs/-/plugin-transform-modules-commonjs-7.16.8.tgz#cdee19aae887b16b9d331009aa9a219af7c86afe"
-  integrity sha512-oflKPvsLT2+uKQopesJt3ApiaIS2HW+hzHFcwRNtyDGieAeC/dIHZX8buJQ2J2X1rxGPy4eRcUijm3qcSPjYcA==
-  dependencies:
-    "@babel/helper-module-transforms" "^7.16.7"
-    "@babel/helper-plugin-utils" "^7.16.7"
-    "@babel/helper-simple-access" "^7.16.7"
-    babel-plugin-dynamic-import-node "^2.3.3"
-
-"@babel/plugin-transform-modules-systemjs@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-modules-systemjs/-/plugin-transform-modules-systemjs-7.16.7.tgz#887cefaef88e684d29558c2b13ee0563e287c2d7"
-  integrity sha512-DuK5E3k+QQmnOqBR9UkusByy5WZWGRxfzV529s9nPra1GE7olmxfqO2FHobEOYSPIjPBTr4p66YDcjQnt8cBmw==
-  dependencies:
-    "@babel/helper-hoist-variables" "^7.16.7"
-    "@babel/helper-module-transforms" "^7.16.7"
-    "@babel/helper-plugin-utils" "^7.16.7"
-    "@babel/helper-validator-identifier" "^7.16.7"
-    babel-plugin-dynamic-import-node "^2.3.3"
-
-"@babel/plugin-transform-modules-umd@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-modules-umd/-/plugin-transform-modules-umd-7.16.7.tgz#23dad479fa585283dbd22215bff12719171e7618"
-  integrity sha512-EMh7uolsC8O4xhudF2F6wedbSHm1HHZ0C6aJ7K67zcDNidMzVcxWdGr+htW9n21klm+bOn+Rx4CBsAntZd3rEQ==
-  dependencies:
-    "@babel/helper-module-transforms" "^7.16.7"
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-named-capturing-groups-regex@^7.16.8":
-  version "7.16.8"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-named-capturing-groups-regex/-/plugin-transform-named-capturing-groups-regex-7.16.8.tgz#7f860e0e40d844a02c9dcf9d84965e7dfd666252"
-  integrity sha512-j3Jw+n5PvpmhRR+mrgIh04puSANCk/T/UA3m3P1MjJkhlK906+ApHhDIqBQDdOgL/r1UYpz4GNclTXxyZrYGSw==
-  dependencies:
-    "@babel/helper-create-regexp-features-plugin" "^7.16.7"
-
-"@babel/plugin-transform-new-target@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-new-target/-/plugin-transform-new-target-7.16.7.tgz#9967d89a5c243818e0800fdad89db22c5f514244"
-  integrity sha512-xiLDzWNMfKoGOpc6t3U+etCE2yRnn3SM09BXqWPIZOBpL2gvVrBWUKnsJx0K/ADi5F5YC5f8APFfWrz25TdlGg==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-object-super@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-object-super/-/plugin-transform-object-super-7.16.7.tgz#ac359cf8d32cf4354d27a46867999490b6c32a94"
-  integrity sha512-14J1feiQVWaGvRxj2WjyMuXS2jsBkgB3MdSN5HuC2G5nRspa5RK9COcs82Pwy5BuGcjb+fYaUj94mYcOj7rCvw==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-    "@babel/helper-replace-supers" "^7.16.7"
-
-"@babel/plugin-transform-parameters@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-parameters/-/plugin-transform-parameters-7.16.7.tgz#a1721f55b99b736511cb7e0152f61f17688f331f"
-  integrity sha512-AT3MufQ7zZEhU2hwOA11axBnExW0Lszu4RL/tAlUJBuNoRak+wehQW8h6KcXOcgjY42fHtDxswuMhMjFEuv/aw==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-property-literals@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-property-literals/-/plugin-transform-property-literals-7.16.7.tgz#2dadac85155436f22c696c4827730e0fe1057a55"
-  integrity sha512-z4FGr9NMGdoIl1RqavCqGG+ZuYjfZ/hkCIeuH6Do7tXmSm0ls11nYVSJqFEUOSJbDab5wC6lRE/w6YjVcr6Hqw==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-regenerator@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-regenerator/-/plugin-transform-regenerator-7.16.7.tgz#9e7576dc476cb89ccc5096fff7af659243b4adeb"
-  integrity sha512-mF7jOgGYCkSJagJ6XCujSQg+6xC1M77/03K2oBmVJWoFGNUtnVJO4WHKJk3dnPC8HCcj4xBQP1Egm8DWh3Pb3Q==
-  dependencies:
-    regenerator-transform "^0.14.2"
-
-"@babel/plugin-transform-reserved-words@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-reserved-words/-/plugin-transform-reserved-words-7.16.7.tgz#1d798e078f7c5958eec952059c460b220a63f586"
-  integrity sha512-KQzzDnZ9hWQBjwi5lpY5v9shmm6IVG0U9pB18zvMu2i4H90xpT4gmqwPYsn8rObiadYe2M0gmgsiOIF5A/2rtg==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-shorthand-properties@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-shorthand-properties/-/plugin-transform-shorthand-properties-7.16.7.tgz#e8549ae4afcf8382f711794c0c7b6b934c5fbd2a"
-  integrity sha512-hah2+FEnoRoATdIb05IOXf+4GzXYTq75TVhIn1PewihbpyrNWUt2JbudKQOETWw6QpLe+AIUpJ5MVLYTQbeeUg==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-spread@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-spread/-/plugin-transform-spread-7.16.7.tgz#a303e2122f9f12e0105daeedd0f30fb197d8ff44"
-  integrity sha512-+pjJpgAngb53L0iaA5gU/1MLXJIfXcYepLgXB3esVRf4fqmj8f2cxM3/FKaHsZms08hFQJkFccEWuIpm429TXg==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-    "@babel/helper-skip-transparent-expression-wrappers" "^7.16.0"
-
-"@babel/plugin-transform-sticky-regex@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-sticky-regex/-/plugin-transform-sticky-regex-7.16.7.tgz#c84741d4f4a38072b9a1e2e3fd56d359552e8660"
-  integrity sha512-NJa0Bd/87QV5NZZzTuZG5BPJjLYadeSZ9fO6oOUoL4iQx+9EEuw/eEM92SrsT19Yc2jgB1u1hsjqDtH02c3Drw==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-template-literals@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-template-literals/-/plugin-transform-template-literals-7.16.7.tgz#f3d1c45d28967c8e80f53666fc9c3e50618217ab"
-  integrity sha512-VwbkDDUeenlIjmfNeDX/V0aWrQH2QiVyJtwymVQSzItFDTpxfyJh3EVaQiS0rIN/CqbLGr0VcGmuwyTdZtdIsA==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-typeof-symbol@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-typeof-symbol/-/plugin-transform-typeof-symbol-7.16.7.tgz#9cdbe622582c21368bd482b660ba87d5545d4f7e"
-  integrity sha512-p2rOixCKRJzpg9JB4gjnG4gjWkWa89ZoYUnl9snJ1cWIcTH/hvxZqfO+WjG6T8DRBpctEol5jw1O5rA8gkCokQ==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-unicode-escapes@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-unicode-escapes/-/plugin-transform-unicode-escapes-7.16.7.tgz#da8717de7b3287a2c6d659750c964f302b31ece3"
-  integrity sha512-TAV5IGahIz3yZ9/Hfv35TV2xEm+kaBDaZQCn2S/hG9/CZ0DktxJv9eKfPc7yYCvOYR4JGx1h8C+jcSOvgaaI/Q==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/plugin-transform-unicode-regex@^7.16.7":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/plugin-transform-unicode-regex/-/plugin-transform-unicode-regex-7.16.7.tgz#0f7aa4a501198976e25e82702574c34cfebe9ef2"
-  integrity sha512-oC5tYYKw56HO75KZVLQ+R/Nl3Hro9kf8iG0hXoaHP7tjAyCpvqBiSNe6vGrZni1Z6MggmUOC6A7VP7AVmw225Q==
-  dependencies:
-    "@babel/helper-create-regexp-features-plugin" "^7.16.7"
-    "@babel/helper-plugin-utils" "^7.16.7"
-
-"@babel/preset-env@^7.6.0":
-  version "7.16.10"
-  resolved "https://registry.yarnpkg.com/@babel/preset-env/-/preset-env-7.16.10.tgz#84400e6b5ee1efd982f55c61f3b6ac3fb5c8ab57"
-  integrity sha512-iCac3fZn9oOcLqc1N2/copPiX7aoxzsvjeDdXoZobrlbQ6YGgS3bL9HyldOJ8V8AY5P7pFynCATrn7M4dMw0Yg==
-  dependencies:
-    "@babel/compat-data" "^7.16.8"
-    "@babel/helper-compilation-targets" "^7.16.7"
-    "@babel/helper-plugin-utils" "^7.16.7"
-    "@babel/helper-validator-option" "^7.16.7"
-    "@babel/plugin-bugfix-safari-id-destructuring-collision-in-function-expression" "^7.16.7"
-    "@babel/plugin-bugfix-v8-spread-parameters-in-optional-chaining" "^7.16.7"
-    "@babel/plugin-proposal-async-generator-functions" "^7.16.8"
-    "@babel/plugin-proposal-class-properties" "^7.16.7"
-    "@babel/plugin-proposal-class-static-block" "^7.16.7"
-    "@babel/plugin-proposal-dynamic-import" "^7.16.7"
-    "@babel/plugin-proposal-export-namespace-from" "^7.16.7"
-    "@babel/plugin-proposal-json-strings" "^7.16.7"
-    "@babel/plugin-proposal-logical-assignment-operators" "^7.16.7"
-    "@babel/plugin-proposal-nullish-coalescing-operator" "^7.16.7"
-    "@babel/plugin-proposal-numeric-separator" "^7.16.7"
-    "@babel/plugin-proposal-object-rest-spread" "^7.16.7"
-    "@babel/plugin-proposal-optional-catch-binding" "^7.16.7"
-    "@babel/plugin-proposal-optional-chaining" "^7.16.7"
-    "@babel/plugin-proposal-private-methods" "^7.16.7"
-    "@babel/plugin-proposal-private-property-in-object" "^7.16.7"
-    "@babel/plugin-proposal-unicode-property-regex" "^7.16.7"
-    "@babel/plugin-syntax-async-generators" "^7.8.4"
-    "@babel/plugin-syntax-class-properties" "^7.12.13"
-    "@babel/plugin-syntax-class-static-block" "^7.14.5"
-    "@babel/plugin-syntax-dynamic-import" "^7.8.3"
-    "@babel/plugin-syntax-export-namespace-from" "^7.8.3"
-    "@babel/plugin-syntax-json-strings" "^7.8.3"
-    "@babel/plugin-syntax-logical-assignment-operators" "^7.10.4"
-    "@babel/plugin-syntax-nullish-coalescing-operator" "^7.8.3"
-    "@babel/plugin-syntax-numeric-separator" "^7.10.4"
-    "@babel/plugin-syntax-object-rest-spread" "^7.8.3"
-    "@babel/plugin-syntax-optional-catch-binding" "^7.8.3"
-    "@babel/plugin-syntax-optional-chaining" "^7.8.3"
-    "@babel/plugin-syntax-private-property-in-object" "^7.14.5"
-    "@babel/plugin-syntax-top-level-await" "^7.14.5"
-    "@babel/plugin-transform-arrow-functions" "^7.16.7"
-    "@babel/plugin-transform-async-to-generator" "^7.16.8"
-    "@babel/plugin-transform-block-scoped-functions" "^7.16.7"
-    "@babel/plugin-transform-block-scoping" "^7.16.7"
-    "@babel/plugin-transform-classes" "^7.16.7"
-    "@babel/plugin-transform-computed-properties" "^7.16.7"
-    "@babel/plugin-transform-destructuring" "^7.16.7"
-    "@babel/plugin-transform-dotall-regex" "^7.16.7"
-    "@babel/plugin-transform-duplicate-keys" "^7.16.7"
-    "@babel/plugin-transform-exponentiation-operator" "^7.16.7"
-    "@babel/plugin-transform-for-of" "^7.16.7"
-    "@babel/plugin-transform-function-name" "^7.16.7"
-    "@babel/plugin-transform-literals" "^7.16.7"
-    "@babel/plugin-transform-member-expression-literals" "^7.16.7"
-    "@babel/plugin-transform-modules-amd" "^7.16.7"
-    "@babel/plugin-transform-modules-commonjs" "^7.16.8"
-    "@babel/plugin-transform-modules-systemjs" "^7.16.7"
-    "@babel/plugin-transform-modules-umd" "^7.16.7"
-    "@babel/plugin-transform-named-capturing-groups-regex" "^7.16.8"
-    "@babel/plugin-transform-new-target" "^7.16.7"
-    "@babel/plugin-transform-object-super" "^7.16.7"
-    "@babel/plugin-transform-parameters" "^7.16.7"
-    "@babel/plugin-transform-property-literals" "^7.16.7"
-    "@babel/plugin-transform-regenerator" "^7.16.7"
-    "@babel/plugin-transform-reserved-words" "^7.16.7"
-    "@babel/plugin-transform-shorthand-properties" "^7.16.7"
-    "@babel/plugin-transform-spread" "^7.16.7"
-    "@babel/plugin-transform-sticky-regex" "^7.16.7"
-    "@babel/plugin-transform-template-literals" "^7.16.7"
-    "@babel/plugin-transform-typeof-symbol" "^7.16.7"
-    "@babel/plugin-transform-unicode-escapes" "^7.16.7"
-    "@babel/plugin-transform-unicode-regex" "^7.16.7"
-    "@babel/preset-modules" "^0.1.5"
-    "@babel/types" "^7.16.8"
-    babel-plugin-polyfill-corejs2 "^0.3.0"
-    babel-plugin-polyfill-corejs3 "^0.5.0"
-    babel-plugin-polyfill-regenerator "^0.3.0"
-    core-js-compat "^3.20.2"
-    semver "^6.3.0"
-
-"@babel/preset-modules@^0.1.5":
-  version "0.1.5"
-  resolved "https://registry.yarnpkg.com/@babel/preset-modules/-/preset-modules-0.1.5.tgz#ef939d6e7f268827e1841638dc6ff95515e115d9"
-  integrity sha512-A57th6YRG7oR3cq/yt/Y84MvGgE0eJG2F1JLhKuyG+jFxEgrd/HAMJatiFtmOiZurz+0DkrvbheCLaV5f2JfjA==
-  dependencies:
-    "@babel/helper-plugin-utils" "^7.0.0"
-    "@babel/plugin-proposal-unicode-property-regex" "^7.4.4"
-    "@babel/plugin-transform-dotall-regex" "^7.4.4"
-    "@babel/types" "^7.4.4"
-    esutils "^2.0.2"
-
-"@babel/runtime@^7.8.4":
-  version "7.16.7"
-  resolved "https://registry.yarnpkg.com/@babel/runtime/-/runtime-7.16.7.tgz#03ff99f64106588c9c403c6ecb8c3bafbbdff1fa"
-  integrity sha512-9E9FJowqAsytyOY6LG+1KuueckRL+aQW+mKvXRXnuFGyRAyepJPmEo9vgMfXUA6O9u3IeEdv9MAkppFcaQwogQ==
-  dependencies:
-    regenerator-runtime "^0.13.4"
-
 "@babel/template@^7.16.7":
   version "7.16.7"
   resolved "https://registry.yarnpkg.com/@babel/template/-/template-7.16.7.tgz#8d126c8701fde4d66b264b3eba3d96f07666d155"
@@ -1014,7 +311,7 @@
     "@babel/parser" "^7.16.7"
     "@babel/types" "^7.16.7"
 
-"@babel/traverse@^7.13.0", "@babel/traverse@^7.16.10", "@babel/traverse@^7.16.8":
+"@babel/traverse@^7.16.10":
   version "7.16.10"
   resolved "https://registry.yarnpkg.com/@babel/traverse/-/traverse-7.16.10.tgz#448f940defbe95b5a8029975b051f75993e8239f"
   integrity sha512-yzuaYXoRJBGMlBhsMJoUW7G1UmSb/eXr/JHYM/MsOJgavJibLwASijW7oXBdw3NQ6T0bW7Ty5P/VarOs9cHmqw==
@@ -1046,7 +343,7 @@
     debug "^4.1.0"
     globals "^11.1.0"
 
-"@babel/types@^7.16.0", "@babel/types@^7.16.7", "@babel/types@^7.16.8", "@babel/types@^7.4.4":
+"@babel/types@^7.16.7", "@babel/types@^7.16.8":
   version "7.16.8"
   resolved "https://registry.yarnpkg.com/@babel/types/-/types-7.16.8.tgz#0ba5da91dd71e0a4e7781a30f22770831062e3c1"
   integrity sha512-smN2DQc5s4M7fntyjGtyIPbRJv6wW4rU/94fmYJ7PKQuZkC0qGMHXJbg6sNGt12JmVr4k5YaptI/XtiLJBnmIg==
@@ -1253,11 +550,31 @@
     "@angular-devkit/schematics" "13.1.4"
     jsonc-parser "3.0.0"
 
+"@socket.io/base64-arraybuffer@~1.0.2":
+  version "1.0.2"
+  resolved "https://registry.yarnpkg.com/@socket.io/base64-arraybuffer/-/base64-arraybuffer-1.0.2.tgz#568d9beae00b0d835f4f8c53fd55714986492e61"
+  integrity sha512-dOlCBKnDw4iShaIsH/bxujKTM18+2TOAsYz+KSc11Am38H4q5Xw8Bbz97ZYdrVNM+um3p7w86Bvvmcn9q+5+eQ==
+
 "@tootallnate/once@1":
   version "1.1.2"
   resolved "https://registry.yarnpkg.com/@tootallnate/once/-/once-1.1.2.tgz#ccb91445360179a04e7fe6aff78c00ffc1eeaf82"
   integrity sha512-RbzJvlNzmRq5c3O09UipeuXno4tA1FE6ikOjxZK0tuxVv3412l64l5t1W5pj4+rJq9vpkm/kwiR07aZXnsKPxw==
 
+"@types/component-emitter@^1.2.10":
+  version "1.2.11"
+  resolved "https://registry.yarnpkg.com/@types/component-emitter/-/component-emitter-1.2.11.tgz#50d47d42b347253817a39709fef03ce66a108506"
+  integrity sha512-SRXjM+tfsSlA9VuG8hGO2nft2p8zjXCK1VcC6N4NXbBbYbSia9kzCChYQajIjzIqOOOuh5Ock6MmV2oux4jDZQ==
+
+"@types/cookie@^0.4.1":
+  version "0.4.1"
+  resolved "https://registry.yarnpkg.com/@types/cookie/-/cookie-0.4.1.tgz#bfd02c1f2224567676c1545199f87c3a861d878d"
+  integrity sha512-XW/Aa8APYr6jSVVA1y/DEIZX0/GMKLEVekNG727R8cs56ahETkRAy/3DR7+fJyh7oUgGwNQaRfXCun0+KbWY7Q==
+
+"@types/cors@^2.8.12":
+  version "2.8.12"
+  resolved "https://registry.yarnpkg.com/@types/cors/-/cors-2.8.12.tgz#6b2c510a7ad7039e98e7b8d3d6598f4359e5c080"
+  integrity sha512-vt+kDhq/M2ayberEtJcIN/hxXy1Pk+59g2FV/ZQceeaTyCtCucjL2Q7FXlFjtWn4n15KCr1NE2lNNFhp0lEThw==
+
 "@types/estree@0.0.39":
   version "0.0.39"
   resolved "https://registry.yarnpkg.com/@types/estree/-/estree-0.0.39.tgz#e177e699ee1b8c22d23174caaa7422644389509f"
@@ -1268,6 +585,11 @@
   resolved "https://registry.yarnpkg.com/@types/flatbuffers/-/flatbuffers-1.10.0.tgz#aa74e30ffdc86445f2f060e1808fc9d56b5603ba"
   integrity sha512-7btbphLrKvo5yl/5CC2OCxUSMx1wV1wvGT1qDXkSt7yi00/YW7E8k6qzXqJHsp+WU0eoG7r6MTQQXI9lIvd0qA==
 
+"@types/jasmine@latest":
+  version "3.10.3"
+  resolved "https://registry.yarnpkg.com/@types/jasmine/-/jasmine-3.10.3.tgz#a89798b3d5a8bd23ca56e855a9aee3e5a93bdaaa"
+  integrity sha512-SWyMrjgdAUHNQmutvDcKablrJhkDLy4wunTme8oYLjKp41GnHGxMRXr2MQMvy/qy8H3LdzwQk9gH4hZ6T++H8g==
+
 "@types/long@^4.0.0":
   version "4.0.0"
   resolved "https://registry.yarnpkg.com/@types/long/-/long-4.0.0.tgz#719551d2352d301ac8b81db732acb6bdc28dbdef"
@@ -1278,11 +600,21 @@
   resolved "https://registry.yarnpkg.com/@types/node/-/node-17.0.8.tgz#50d680c8a8a78fe30abe6906453b21ad8ab0ad7b"
   integrity sha512-YofkM6fGv4gDJq78g4j0mMuGMkZVxZDgtU0JRdx6FgiJDG+0fY0GKVolOV8WqVmEhLCXkQRjwDdKyPxJp/uucg==
 
+"@types/node@>=10.0.0":
+  version "17.0.10"
+  resolved "https://registry.yarnpkg.com/@types/node/-/node-17.0.10.tgz#616f16e9d3a2a3d618136b1be244315d95bd7cab"
+  integrity sha512-S/3xB4KzyFxYGCppyDt68yzBU9ysL88lSdIah4D6cptdcltc4NCPCAMc0+PCpg/lLIyC7IPvj2Z52OJWeIUkog==
+
 "@types/node@^10.1.0":
   version "10.14.18"
   resolved "https://registry.yarnpkg.com/@types/node/-/node-10.14.18.tgz#b7d45fc950e6ffd7edc685e890d13aa7b8535dce"
   integrity sha512-ryO3Q3++yZC/+b8j8BdKd/dn9JlzlHBPdm80656xwYUdmPkpTGTjkAdt6BByiNupGPE8w0FhBgvYy/fX9hRNGQ==
 
+"@types/node@latest":
+  version "17.0.12"
+  resolved "https://registry.yarnpkg.com/@types/node/-/node-17.0.12.tgz#f7aa331b27f08244888c47b7df126184bc2339c5"
+  integrity sha512-4YpbAsnJXWYK/fpTVFlMIcUIho2AYCi4wg5aNPrG1ng7fn/1/RZfCIpRCiBX+12RVa34RluilnvCqD+g3KiSiA==
+
 "@types/resolve@1.17.1":
   version "1.17.1"
   resolved "https://registry.yarnpkg.com/@types/resolve/-/resolve-1.17.1.tgz#3afd6ad8967c77e4376c598a82ddd58f46ec45d6"
@@ -1300,6 +632,14 @@
   resolved "https://registry.yarnpkg.com/abbrev/-/abbrev-1.1.1.tgz#f8f2c887ad10bf67f634f005b6987fed3179aac8"
   integrity sha512-nne9/IiQ/hzIhY6pdDnbBtz7DjPTKrY00P/zvPSm5pOFkl6xuGrGnXn/VtTNNfNtAfZ9/1RtehkszU9qcTii0Q==
 
+accepts@~1.3.4:
+  version "1.3.7"
+  resolved "https://registry.yarnpkg.com/accepts/-/accepts-1.3.7.tgz#531bc726517a3b2b41f850021c6cc15eaab507cd"
+  integrity sha512-Il80Qs2WjYlJIBNzNkK6KYqlVMTbZLXgHx2oT0pU/fjRHyEp+PEfEPY0R3WCwAGVOtauxh1hOxNgIf5bv7dQpA==
+  dependencies:
+    mime-types "~2.1.24"
+    negotiator "0.6.2"
+
 agent-base@6, agent-base@^6.0.2:
   version "6.0.2"
   resolved "https://registry.yarnpkg.com/agent-base/-/agent-base-6.0.2.tgz#49fff58577cfee3f37176feab4c22e00f86d7f77"
@@ -1403,37 +743,6 @@
     delegates "^1.0.0"
     readable-stream "^3.6.0"
 
-babel-plugin-dynamic-import-node@^2.3.3:
-  version "2.3.3"
-  resolved "https://registry.yarnpkg.com/babel-plugin-dynamic-import-node/-/babel-plugin-dynamic-import-node-2.3.3.tgz#84fda19c976ec5c6defef57f9427b3def66e17a3"
-  integrity sha512-jZVI+s9Zg3IqA/kdi0i6UDCybUI3aSBLnglhYbSSjKlV7yF1F/5LWv8MakQmvYpnbJDS6fcBL2KzHSxNCMtWSQ==
-  dependencies:
-    object.assign "^4.1.0"
-
-babel-plugin-polyfill-corejs2@^0.3.0:
-  version "0.3.1"
-  resolved "https://registry.yarnpkg.com/babel-plugin-polyfill-corejs2/-/babel-plugin-polyfill-corejs2-0.3.1.tgz#440f1b70ccfaabc6b676d196239b138f8a2cfba5"
-  integrity sha512-v7/T6EQcNfVLfcN2X8Lulb7DjprieyLWJK/zOWH5DUYcAgex9sP3h25Q+DLsX9TloXe3y1O8l2q2Jv9q8UVB9w==
-  dependencies:
-    "@babel/compat-data" "^7.13.11"
-    "@babel/helper-define-polyfill-provider" "^0.3.1"
-    semver "^6.1.1"
-
-babel-plugin-polyfill-corejs3@^0.5.0:
-  version "0.5.1"
-  resolved "https://registry.yarnpkg.com/babel-plugin-polyfill-corejs3/-/babel-plugin-polyfill-corejs3-0.5.1.tgz#d66183bf10976ea677f4149a7fcc4d8df43d4060"
-  integrity sha512-TihqEe4sQcb/QcPJvxe94/9RZuLQuF1+To4WqQcRvc+3J3gLCPIPgDKzGLG6zmQLfH3nn25heRuDNkS2KR4I8A==
-  dependencies:
-    "@babel/helper-define-polyfill-provider" "^0.3.1"
-    core-js-compat "^3.20.0"
-
-babel-plugin-polyfill-regenerator@^0.3.0:
-  version "0.3.1"
-  resolved "https://registry.yarnpkg.com/babel-plugin-polyfill-regenerator/-/babel-plugin-polyfill-regenerator-0.3.1.tgz#2c0678ea47c75c8cc2fbb1852278d8fb68233990"
-  integrity sha512-Y2B06tvgHYt1x0yz17jGkGeeMr5FeKUu+ASJ+N6nB5lQ8Dapfg42i0OVrf8PNGJ3zKL4A23snMi1IRwrqqND7A==
-  dependencies:
-    "@babel/helper-define-polyfill-provider" "^0.3.1"
-
 balanced-match@^1.0.0:
   version "1.0.2"
   resolved "https://registry.yarnpkg.com/balanced-match/-/balanced-match-1.0.2.tgz#e83e3a7e3f300b34cb9d87f615fa0cbf357690ee"
@@ -1444,6 +753,11 @@
   resolved "https://registry.yarnpkg.com/base64-js/-/base64-js-1.5.1.tgz#1b1b440160a5bf7ad40b650f095963481903930a"
   integrity sha512-AKpaYlHn8t4SVbOHCy+b5+KKgvR4vrsD8vbvrbiQJps7fKDTkjkDry6ji0rUJjC0kzbNePLwzxq8iypo41qeWA==
 
+base64id@2.0.0, base64id@~2.0.0:
+  version "2.0.0"
+  resolved "https://registry.yarnpkg.com/base64id/-/base64id-2.0.0.tgz#2770ac6bc47d312af97a8bf9a634342e0cd25cb6"
+  integrity sha512-lGe34o6EHj9y3Kts9R4ZYs/Gr+6N7MCaMlIFA3F1R2O5/m7K06AxfSeO5530PEERE6/WyEg3lsuyw4GHlPZHog==
+
 binary-extensions@^2.0.0:
   version "2.2.0"
   resolved "https://registry.yarnpkg.com/binary-extensions/-/binary-extensions-2.2.0.tgz#75f502eeaf9ffde42fc98829645be4ea76bd9e2d"
@@ -1458,6 +772,22 @@
     inherits "^2.0.4"
     readable-stream "^3.4.0"
 
+body-parser@^1.19.0:
+  version "1.19.1"
+  resolved "https://registry.yarnpkg.com/body-parser/-/body-parser-1.19.1.tgz#1499abbaa9274af3ecc9f6f10396c995943e31d4"
+  integrity sha512-8ljfQi5eBk8EJfECMrgqNGWPEY5jWP+1IzkzkGdFFEwFQZZyaZ21UqdaHktgiMlH0xLHqIFtE/u2OYE5dOtViA==
+  dependencies:
+    bytes "3.1.1"
+    content-type "~1.0.4"
+    debug "2.6.9"
+    depd "~1.1.2"
+    http-errors "1.8.1"
+    iconv-lite "0.4.24"
+    on-finished "~2.3.0"
+    qs "6.9.6"
+    raw-body "2.4.2"
+    type-is "~1.6.18"
+
 brace-expansion@^1.1.7:
   version "1.1.11"
   resolved "https://registry.yarnpkg.com/brace-expansion/-/brace-expansion-1.1.11.tgz#3c7fcbf529d87226f3d2f52b966ff5271eb441dd"
@@ -1466,14 +796,14 @@
     balanced-match "^1.0.0"
     concat-map "0.0.1"
 
-braces@~3.0.2:
+braces@^3.0.2, braces@~3.0.2:
   version "3.0.2"
   resolved "https://registry.yarnpkg.com/braces/-/braces-3.0.2.tgz#3454e1a462ee8d599e236df336cd9ea4f8afe107"
   integrity sha512-b8um+L1RzM3WDSzvhm6gIz1yfTbBt6YTlcEKAvsmqCZZFw46z626lVj9j1yEPW33H5H+lBQpZMP1k8l+78Ha0A==
   dependencies:
     fill-range "^7.0.1"
 
-browserslist@^4.17.5, browserslist@^4.19.1:
+browserslist@^4.17.5:
   version "4.19.1"
   resolved "https://registry.yarnpkg.com/browserslist/-/browserslist-4.19.1.tgz#4ac0435b35ab655896c31d53018b6dd5e9e4c9a3"
   integrity sha512-u2tbbG5PdKRTUoctO3NBD8FQ5HdPh1ZXPHzp1rwaa5jTc+RV9/+RlWiAIKmjRPQF+xbGM9Kklj5bZQFa2s/38A==
@@ -1506,6 +836,11 @@
   resolved "https://registry.yarnpkg.com/builtins/-/builtins-1.0.3.tgz#cb94faeb61c8696451db36534e1422f94f0aee88"
   integrity sha1-y5T662HIaWRR2zZTThQi+U8K7og=
 
+bytes@3.1.1:
+  version "3.1.1"
+  resolved "https://registry.yarnpkg.com/bytes/-/bytes-3.1.1.tgz#3f018291cb4cbad9accb6e6970bca9c8889e879a"
+  integrity sha512-dWe4nWO/ruEOY7HkUJ5gFt1DCFV9zPRoJr8pV0/ASQermOZjtq8jMjOprC0Kd10GLN+l7xaUPvxzJFWtxGu8Fg==
+
 cacache@^15.0.5, cacache@^15.2.0:
   version "15.3.0"
   resolved "https://registry.yarnpkg.com/cacache/-/cacache-15.3.0.tgz#dc85380fb2f556fe3dda4c719bfa0ec875a7f1eb"
@@ -1530,14 +865,6 @@
     tar "^6.0.2"
     unique-filename "^1.1.1"
 
-call-bind@^1.0.0:
-  version "1.0.2"
-  resolved "https://registry.yarnpkg.com/call-bind/-/call-bind-1.0.2.tgz#b1d4e89e688119c3c9a903ad30abb2f6a919be3c"
-  integrity sha512-7O+FbCihrB5WGbFYesctwmTKae6rOiIzmz1icreWJ+0aA7LJfuqhEso2T9ncpcFtzMQtzXf2QGGueWJGTYsqrA==
-  dependencies:
-    function-bind "^1.1.1"
-    get-intrinsic "^1.0.2"
-
 caniuse-lite@^1.0.30001286:
   version "1.0.30001299"
   resolved "https://registry.yarnpkg.com/caniuse-lite/-/caniuse-lite-1.0.30001299.tgz#d753bf6444ed401eb503cbbe17aa3e1451b5a68c"
@@ -1585,7 +912,7 @@
   optionalDependencies:
     fsevents "~2.3.2"
 
-chokidar@^3.4.0:
+chokidar@^3.4.0, chokidar@^3.5.1:
   version "3.5.3"
   resolved "https://registry.yarnpkg.com/chokidar/-/chokidar-3.5.3.tgz#1cf37c8707b932bd1af1ae22c0432e2acd1903bd"
   integrity sha512-Dr3sfKRP6oTcjf2JmUmFJfeVMvXBdegxB0iVQ5eb2V10uFJUCAS8OByZdVAyVb8xXNz3GjjTgj9kLWsZTqE6kw==
@@ -1670,6 +997,11 @@
   resolved "https://registry.yarnpkg.com/color-support/-/color-support-1.1.3.tgz#93834379a1cc9a0c61f82f52f0d04322251bd5a2"
   integrity sha512-qiBjkpbMLO/HL68y+lh4q0/O1MZFj2RX6X/KmMa3+gJD3z+WwI1ZzDHysvqHGS3mP6mznPckpXmw1nI9cJjyRg==
 
+colors@1.4.0:
+  version "1.4.0"
+  resolved "https://registry.yarnpkg.com/colors/-/colors-1.4.0.tgz#c50491479d4c1bdaed2c9ced32cf7c7dc2360f78"
+  integrity sha512-a+UqTh4kgZg/SlGvfbzDHpgRu7AAQOmmqRHJnxhRZICKFUT91brVhNNt58CMWU9PsBbv3PDCZUHbVxuDiH2mtA==
+
 commander@^2.20.0:
   version "2.20.3"
   resolved "https://registry.yarnpkg.com/commander/-/commander-2.20.3.tgz#fd485e84c03eb4881c20722ba48035e8531aeb33"
@@ -1680,16 +1012,36 @@
   resolved "https://registry.yarnpkg.com/commander/-/commander-4.1.1.tgz#9fd602bd936294e9e9ef46a3f4d6964044b18068"
   integrity sha512-NOKm8xhkzAjzFx8B2v5OAHT+u5pRQc2UCa2Vq9jYL/31o2wi9mxBA7LIFs3sV5VSC49z6pEhfbMULvShKj26WA==
 
+component-emitter@~1.3.0:
+  version "1.3.0"
+  resolved "https://registry.yarnpkg.com/component-emitter/-/component-emitter-1.3.0.tgz#16e4070fba8ae29b679f2215853ee181ab2eabc0"
+  integrity sha512-Rd3se6QB+sO1TwqZjscQrurpEPIfO0/yYnSin6Q/rD3mOutHvUrCAhJub3r90uNb+SESBuE0QYoB90YdfatsRg==
+
 concat-map@0.0.1:
   version "0.0.1"
   resolved "https://registry.yarnpkg.com/concat-map/-/concat-map-0.0.1.tgz#d8a96bd77fd68df7793a73036a3ba0d5405d477b"
   integrity sha1-2Klr13/Wjfd5OnMDajug1UBdR3s=
 
+connect@^3.7.0:
+  version "3.7.0"
+  resolved "https://registry.yarnpkg.com/connect/-/connect-3.7.0.tgz#5d49348910caa5e07a01800b030d0c35f20484f8"
+  integrity sha512-ZqRXc+tZukToSNmh5C2iWMSoV3X1YUcPbqEM4DkEG5tNQXrQUZCNVGGv3IuicnkMtPfGf3Xtp8WCXs295iQ1pQ==
+  dependencies:
+    debug "2.6.9"
+    finalhandler "1.1.2"
+    parseurl "~1.3.3"
+    utils-merge "1.0.1"
+
 console-control-strings@^1.0.0, console-control-strings@^1.1.0:
   version "1.1.0"
   resolved "https://registry.yarnpkg.com/console-control-strings/-/console-control-strings-1.1.0.tgz#3d7cf4464db6446ea644bf4b39507f9851008e8e"
   integrity sha1-PXz0Rk22RG6mRL9LOVB/mFEAjo4=
 
+content-type@~1.0.4:
+  version "1.0.4"
+  resolved "https://registry.yarnpkg.com/content-type/-/content-type-1.0.4.tgz#e138cc75e040c727b1966fe5e5f8c9aee256fe3b"
+  integrity sha512-hIP3EEPs8tB9AT1L+NUqtwOAps4mk2Zob89MWXMHjHWg9milF/j4osnnQLXBCBFBk/tvIG/tUc9mOUJiPBhPXA==
+
 convert-source-map@^1.1.0, convert-source-map@^1.5.1, convert-source-map@^1.7.0:
   version "1.8.0"
   resolved "https://registry.yarnpkg.com/convert-source-map/-/convert-source-map-1.8.0.tgz#f3373c32d21b4d780dd8004514684fb791ca4369"
@@ -1697,15 +1049,37 @@
   dependencies:
     safe-buffer "~5.1.1"
 
-core-js-compat@^3.20.0, core-js-compat@^3.20.2:
-  version "3.20.3"
-  resolved "https://registry.yarnpkg.com/core-js-compat/-/core-js-compat-3.20.3.tgz#d71f85f94eb5e4bea3407412e549daa083d23bd6"
-  integrity sha512-c8M5h0IkNZ+I92QhIpuSijOxGAcj3lgpsWdkCqmUTZNwidujF4r3pi6x1DCN+Vcs5qTS2XWWMfWSuCqyupX8gw==
-  dependencies:
-    browserslist "^4.19.1"
-    semver "7.0.0"
+cookie@~0.4.1:
+  version "0.4.1"
+  resolved "https://registry.yarnpkg.com/cookie/-/cookie-0.4.1.tgz#afd713fe26ebd21ba95ceb61f9a8116e50a537d1"
+  integrity sha512-ZwrFkGJxUR3EIoXtO+yVE69Eb7KlixbaeAWfBQB9vVsNn/o+Yw69gBWSSDK825hQNdN+wF8zELf3dFNl/kxkUA==
 
-debug@4, debug@4.3.3, debug@^4.1.0, debug@^4.1.1, debug@^4.3.1:
+cors@~2.8.5:
+  version "2.8.5"
+  resolved "https://registry.yarnpkg.com/cors/-/cors-2.8.5.tgz#eac11da51592dd86b9f06f6e7ac293b3df875d29"
+  integrity sha512-KIHbLJqu73RGr/hnbrO9uBeixNGuvSQjul/jdFvS/KFSIH1hWVd1ng7zOHx+YrEfInLG7q4n6GHQ9cDtxv/P6g==
+  dependencies:
+    object-assign "^4"
+    vary "^1"
+
+custom-event@~1.0.0:
+  version "1.0.1"
+  resolved "https://registry.yarnpkg.com/custom-event/-/custom-event-1.0.1.tgz#5d02a46850adf1b4a317946a3928fccb5bfd0425"
+  integrity sha1-XQKkaFCt8bSjF5RqOSj8y1v9BCU=
+
+date-format@^4.0.3:
+  version "4.0.3"
+  resolved "https://registry.yarnpkg.com/date-format/-/date-format-4.0.3.tgz#f63de5dc08dc02efd8ef32bf2a6918e486f35873"
+  integrity sha512-7P3FyqDcfeznLZp2b+OMitV9Sz2lUnsT87WaTat9nVwqsBkTzPG3lPLNwW3en6F4pHUiWzr6vb8CLhjdK9bcxQ==
+
+debug@2.6.9:
+  version "2.6.9"
+  resolved "https://registry.yarnpkg.com/debug/-/debug-2.6.9.tgz#5d128515df134ff327e90a4c93f4e077a536341f"
+  integrity sha512-bC7ElrdJaJnPbAP+1EotYvqZsb3ecl5wi6Bfi6BJTUcNowp6cvspg0jXznRTKDjm/E7AdgFBVeAPVMNcKGsHMA==
+  dependencies:
+    ms "2.0.0"
+
+debug@4, debug@4.3.3, debug@^4.1.0, debug@^4.1.1, debug@^4.3.1, debug@^4.3.3, debug@~4.3.1, debug@~4.3.2:
   version "4.3.3"
   resolved "https://registry.yarnpkg.com/debug/-/debug-4.3.3.tgz#04266e0b70a98d4462e6e288e38259213332b664"
   integrity sha512-/zxw5+vh1Tfv+4Qn7a5nsbcJKPaSvCDhojn6FEl9vupwK2VCSDtEiEtqr8DFtzYFOdz63LBkxec7DYuc2jon6Q==
@@ -1729,19 +1103,12 @@
   resolved "https://registry.yarnpkg.com/define-lazy-prop/-/define-lazy-prop-2.0.0.tgz#3f7ae421129bcaaac9bc74905c98a0009ec9ee7f"
   integrity sha512-Ds09qNh8yw3khSjiJjiUInaGX9xlqZDY7JVryGxdxV7NPeuqQfplOpQ66yJFZut3jLa5zOwkXw1g9EI2uKh4Og==
 
-define-properties@^1.1.3:
-  version "1.1.3"
-  resolved "https://registry.yarnpkg.com/define-properties/-/define-properties-1.1.3.tgz#cf88da6cbee26fe6db7094f61d870cbd84cee9f1"
-  integrity sha512-3MqfYKj2lLzdMSf8ZIZE/V+Zuy+BgD6f164e8K2w7dgnpKArBDerGYpM46IYYcjnkdPNMjPk9A6VFB8+3SKlXQ==
-  dependencies:
-    object-keys "^1.0.12"
-
 delegates@^1.0.0:
   version "1.0.0"
   resolved "https://registry.yarnpkg.com/delegates/-/delegates-1.0.0.tgz#84c6e159b81904fdca59a0ef44cd870d31250f9a"
   integrity sha1-hMbhWbgZBP3KWaDvRM2HDTElD5o=
 
-depd@^1.1.2:
+depd@^1.1.2, depd@~1.1.2:
   version "1.1.2"
   resolved "https://registry.yarnpkg.com/depd/-/depd-1.1.2.tgz#9bcd52e14c097763e749b274c4346ed2e560b5a9"
   integrity sha1-m81S4UwJd2PnSbJ0xDRu0uVgtak=
@@ -1751,6 +1118,26 @@
   resolved "https://registry.yarnpkg.com/dependency-graph/-/dependency-graph-0.11.0.tgz#ac0ce7ed68a54da22165a85e97a01d53f5eb2e27"
   integrity sha512-JeMq7fEshyepOWDfcfHK06N3MhyPhz++vtqWhMT5O9A3K42rdsEDpfdVqjaqaAhsw6a+ZqeDvQVtD0hFHQWrzg==
 
+di@^0.0.1:
+  version "0.0.1"
+  resolved "https://registry.yarnpkg.com/di/-/di-0.0.1.tgz#806649326ceaa7caa3306d75d985ea2748ba913c"
+  integrity sha1-gGZJMmzqp8qjMG112YXqJ0i6kTw=
+
+dom-serialize@^2.2.1:
+  version "2.2.1"
+  resolved "https://registry.yarnpkg.com/dom-serialize/-/dom-serialize-2.2.1.tgz#562ae8999f44be5ea3076f5419dcd59eb43ac95b"
+  integrity sha1-ViromZ9Evl6jB29UGdzVnrQ6yVs=
+  dependencies:
+    custom-event "~1.0.0"
+    ent "~2.2.0"
+    extend "^3.0.0"
+    void-elements "^2.0.0"
+
+ee-first@1.1.1:
+  version "1.1.1"
+  resolved "https://registry.yarnpkg.com/ee-first/-/ee-first-1.1.1.tgz#590c61156b0ae2f4f0255732a158b266bc56b21d"
+  integrity sha1-WQxhFWsK4vTwJVcyoViyZrxWsh0=
+
 electron-to-chromium@^1.4.17:
   version "1.4.46"
   resolved "https://registry.yarnpkg.com/electron-to-chromium/-/electron-to-chromium-1.4.46.tgz#c88a6fedc766589826db0481602a888864ade1ca"
@@ -1761,6 +1148,11 @@
   resolved "https://registry.yarnpkg.com/emoji-regex/-/emoji-regex-8.0.0.tgz#e818fd69ce5ccfcb404594f842963bf53164cc37"
   integrity sha512-MSjYzcWNOA0ewAHpz0MxpYFvwg6yjy1NG3xteoqz644VCo/RPgnr1/GGt+ic3iJTzQ8Eu3TdM14SawnVUmGE6A==
 
+encodeurl@~1.0.2:
+  version "1.0.2"
+  resolved "https://registry.yarnpkg.com/encodeurl/-/encodeurl-1.0.2.tgz#ad3ff4c86ec2d029322f5a02c3a9a606c95b3f59"
+  integrity sha1-rT/0yG7C0CkyL1oCw6mmBslbP1k=
+
 encoding@^0.1.12:
   version "0.1.13"
   resolved "https://registry.yarnpkg.com/encoding/-/encoding-0.1.13.tgz#56574afdd791f54a8e9b2785c0582a2d26210fa9"
@@ -1768,6 +1160,34 @@
   dependencies:
     iconv-lite "^0.6.2"
 
+engine.io-parser@~5.0.0:
+  version "5.0.3"
+  resolved "https://registry.yarnpkg.com/engine.io-parser/-/engine.io-parser-5.0.3.tgz#ca1f0d7b11e290b4bfda251803baea765ed89c09"
+  integrity sha512-BtQxwF27XUNnSafQLvDi0dQ8s3i6VgzSoQMJacpIcGNrlUdfHSKbgm3jmjCVvQluGzqwujQMPAoMai3oYSTurg==
+  dependencies:
+    "@socket.io/base64-arraybuffer" "~1.0.2"
+
+engine.io@~6.1.0:
+  version "6.1.2"
+  resolved "https://registry.yarnpkg.com/engine.io/-/engine.io-6.1.2.tgz#e7b9d546d90c62246ffcba4d88594be980d3855a"
+  integrity sha512-v/7eGHxPvO2AWsksyx2PUsQvBafuvqs0jJJQ0FdmJG1b9qIvgSbqDRGwNhfk2XHaTTbTXiC4quRE8Q9nRjsrQQ==
+  dependencies:
+    "@types/cookie" "^0.4.1"
+    "@types/cors" "^2.8.12"
+    "@types/node" ">=10.0.0"
+    accepts "~1.3.4"
+    base64id "2.0.0"
+    cookie "~0.4.1"
+    cors "~2.8.5"
+    debug "~4.3.1"
+    engine.io-parser "~5.0.0"
+    ws "~8.2.3"
+
+ent@~2.2.0:
+  version "2.2.0"
+  resolved "https://registry.yarnpkg.com/ent/-/ent-2.2.0.tgz#e964219325a21d05f44466a2f686ed6ce5f5dd1d"
+  integrity sha1-6WQhkyWiHQX0RGai9obtbOX13R0=
+
 env-paths@^2.2.0:
   version "2.2.1"
   resolved "https://registry.yarnpkg.com/env-paths/-/env-paths-2.2.1.tgz#420399d416ce1fbe9bc0a07c62fa68d67fd0f8f2"
@@ -1783,6 +1203,11 @@
   resolved "https://registry.yarnpkg.com/escalade/-/escalade-3.1.1.tgz#d8cfdc7000965c5a0174b4a82eaa5c0552742e40"
   integrity sha512-k0er2gUkLf8O0zKJiAhmkTnJlTvINGv7ygDNPbeIsX/TJjGJZHuh9B2UxbsaEkmlEo9MfhrSzmhIlhRlI2GXnw==
 
+escape-html@~1.0.3:
+  version "1.0.3"
+  resolved "https://registry.yarnpkg.com/escape-html/-/escape-html-1.0.3.tgz#0258eae4d3d0c0974de1c169188ef0051d1d1988"
+  integrity sha1-Aljq5NPQwJdN4cFpGI7wBR0dGYg=
+
 escape-string-regexp@^1.0.5:
   version "1.0.5"
   resolved "https://registry.yarnpkg.com/escape-string-regexp/-/escape-string-regexp-1.0.5.tgz#1b61c0562190a8dff6ae3bb2cf0200ca130b86d4"
@@ -1793,10 +1218,15 @@
   resolved "https://registry.yarnpkg.com/estree-walker/-/estree-walker-1.0.1.tgz#31bc5d612c96b704106b477e6dd5d8aa138cb700"
   integrity sha512-1fMXF3YP4pZZVozF8j/ZLfvnR8NSIljt56UhbZ5PeeDmmGHpgpdwQt7ITlGvYaQukCvuBRMLEiKiYC+oeIg4cg==
 
-esutils@^2.0.2:
-  version "2.0.3"
-  resolved "https://registry.yarnpkg.com/esutils/-/esutils-2.0.3.tgz#74d2eb4de0b8da1293711910d50775b9b710ef64"
-  integrity sha512-kVscqXk4OCp68SZ0dkgEKVi6/8ij300KBWTJq32P/dYeWTSwK41WyTxalN1eRmA5Z9UU/LX9D7FWSmV9SAYx6g==
+eventemitter3@^4.0.0:
+  version "4.0.7"
+  resolved "https://registry.yarnpkg.com/eventemitter3/-/eventemitter3-4.0.7.tgz#2de9b68f6528d5644ef5c59526a1b4a07306169f"
+  integrity sha512-8guHBZCwKnFhYdHr2ysuRWErTwhoN2X8XELRlrRwpmfeY2jjuUN4taQMsULKUVo1K4DvZl+0pgfyoysHxvmvEw==
+
+extend@^3.0.0:
+  version "3.0.2"
+  resolved "https://registry.yarnpkg.com/extend/-/extend-3.0.2.tgz#f8b1136b4071fbd8eb140aff858b1019ec2915fa"
+  integrity sha512-fjquC59cD7CyW6urNXK0FBufkZcoiGG80wTuPujX590cB5Ttln20E2UB4S/WARVqhXffZl2LNgS+gQdPIIim/g==
 
 external-editor@^3.0.3:
   version "3.1.0"
@@ -1831,6 +1261,38 @@
   dependencies:
     to-regex-range "^5.0.1"
 
+finalhandler@1.1.2:
+  version "1.1.2"
+  resolved "https://registry.yarnpkg.com/finalhandler/-/finalhandler-1.1.2.tgz#b7e7d000ffd11938d0fdb053506f6ebabe9f587d"
+  integrity sha512-aAWcW57uxVNrQZqFXjITpW3sIUQmHGG3qSb9mUah9MgMC4NeWhNOlNjXEYq3HjRAvL6arUviZGGJsBg6z0zsWA==
+  dependencies:
+    debug "2.6.9"
+    encodeurl "~1.0.2"
+    escape-html "~1.0.3"
+    on-finished "~2.3.0"
+    parseurl "~1.3.3"
+    statuses "~1.5.0"
+    unpipe "~1.0.0"
+
+flatted@^3.2.4:
+  version "3.2.4"
+  resolved "https://registry.yarnpkg.com/flatted/-/flatted-3.2.4.tgz#28d9969ea90661b5134259f312ab6aa7929ac5e2"
+  integrity sha512-8/sOawo8tJ4QOBX8YlQBMxL8+RLZfxMQOif9o0KUKTNTjMYElWPE0r/m5VNFxTRd0NSw8qSy8dajrwX4RYI1Hw==
+
+follow-redirects@^1.0.0:
+  version "1.14.7"
+  resolved "https://registry.yarnpkg.com/follow-redirects/-/follow-redirects-1.14.7.tgz#2004c02eb9436eee9a21446a6477debf17e81685"
+  integrity sha512-+hbxoLbFMbRKDwohX8GkTataGqO6Jb7jGwpAlwgy2bIz25XtRm7KEzJM76R1WiNT5SwZkX4Y75SwBolkpmE7iQ==
+
+fs-extra@^10.0.0:
+  version "10.0.0"
+  resolved "https://registry.yarnpkg.com/fs-extra/-/fs-extra-10.0.0.tgz#9ff61b655dde53fb34a82df84bb214ce802e17c1"
+  integrity sha512-C5owb14u9eJwizKGdchcDUQeFtlSHHthBk8pbX9Vc1PFZrLombudjDnNns88aYslCyF6IY5SUw3Roz6xShcEIQ==
+  dependencies:
+    graceful-fs "^4.2.0"
+    jsonfile "^6.0.1"
+    universalify "^2.0.0"
+
 fs-minipass@^2.0.0, fs-minipass@^2.1.0:
   version "2.1.0"
   resolved "https://registry.yarnpkg.com/fs-minipass/-/fs-minipass-2.1.0.tgz#7f5036fdbf12c63c169190cbe4199c852271f9fb"
@@ -1883,15 +1345,6 @@
   resolved "https://registry.yarnpkg.com/get-caller-file/-/get-caller-file-2.0.5.tgz#4f94412a82db32f36e3b0b9741f8a97feb031f7e"
   integrity sha512-DyFP3BM/3YHTQOCUL/w0OZHR0lpKeGrxotcHWcqNEdnltqFwXVfhEBQ94eIo34AfQpo0rGki4cyIiftY06h2Fg==
 
-get-intrinsic@^1.0.2:
-  version "1.1.1"
-  resolved "https://registry.yarnpkg.com/get-intrinsic/-/get-intrinsic-1.1.1.tgz#15f59f376f855c446963948f0d24cd3637b4abc6"
-  integrity sha512-kWZrnVM42QCiEA2Ig1bG8zjoIMOgxWwYCEeNdwY6Tv/cOSeGpcoX4pXHfKUxNKVoArnrEr2e9srnAxxGIraS9Q==
-  dependencies:
-    function-bind "^1.1.1"
-    has "^1.0.3"
-    has-symbols "^1.0.1"
-
 glob-parent@~5.1.2:
   version "5.1.2"
   resolved "https://registry.yarnpkg.com/glob-parent/-/glob-parent-5.1.2.tgz#869832c58034fe68a4093c17dc15e8340d8401c4"
@@ -1899,7 +1352,7 @@
   dependencies:
     is-glob "^4.0.1"
 
-glob@^7.0.0, glob@^7.1.3, glob@^7.1.4, glob@^7.1.6:
+glob@^7.0.0, glob@^7.1.3, glob@^7.1.4, glob@^7.1.6, glob@^7.1.7:
   version "7.2.0"
   resolved "https://registry.yarnpkg.com/glob/-/glob-7.2.0.tgz#d15535af7732e02e948f4c41628bd910293f6023"
   integrity sha512-lmLf6gtyrPq8tTjSmrO94wBeQbFR3HbLHbuyD69wuyQkImp2hWqMGB47OX65FBkPffO641IP9jWa1z4ivqG26Q==
@@ -1921,7 +1374,7 @@
   resolved "https://registry.yarnpkg.com/google-protobuf/-/google-protobuf-3.19.1.tgz#5af5390e8206c446d8f49febaffd4b7f4ac28f41"
   integrity sha512-Isv1RlNC+IzZzilcxnlVSf+JvuhxmY7DaxYCBy+zPS9XVuJRtlTTIXR9hnZ1YL1MMusJn/7eSy2swCzZIomQSg==
 
-graceful-fs@^4.2.6:
+graceful-fs@^4.1.2, graceful-fs@^4.1.6, graceful-fs@^4.2.0, graceful-fs@^4.2.6:
   version "4.2.9"
   resolved "https://registry.yarnpkg.com/graceful-fs/-/graceful-fs-4.2.9.tgz#041b05df45755e587a24942279b9d113146e1c96"
   integrity sha512-NtNxqUcXgpW2iMrfqSfR73Glt39K+BLwWsPs94yR63v45T0Wbej7eRmL5cWfwEgqXnmjQp3zaJTshdRW/qC2ZQ==
@@ -1936,11 +1389,6 @@
   resolved "https://registry.yarnpkg.com/has-flag/-/has-flag-4.0.0.tgz#944771fd9c81c81265c4d6941860da06bb59479b"
   integrity sha512-EykJT/Q1KjTWctppgIAgfSO0tKVuZUjhgMr17kqTumMl6Afv3EISleU7qZUzoXDFTAHTDC4NOoG/ZxU3EvlMPQ==
 
-has-symbols@^1.0.1:
-  version "1.0.2"
-  resolved "https://registry.yarnpkg.com/has-symbols/-/has-symbols-1.0.2.tgz#165d3070c00309752a1236a479331e3ac56f1423"
-  integrity sha512-chXa79rL/UC2KlX17jo3vRGz0azaWEx5tGqZg5pO3NUyEJVB17dMruQlzCCOfUvElghKcm5194+BCRvi2Rv/Gw==
-
 has-unicode@^2.0.1:
   version "2.0.1"
   resolved "https://registry.yarnpkg.com/has-unicode/-/has-unicode-2.0.1.tgz#e0e6fe6a28cf51138855e086d1691e771de2a8b9"
@@ -1960,19 +1408,22 @@
   dependencies:
     lru-cache "^6.0.0"
 
-html-insert-assets@^0.14.2:
-  version "0.14.2"
-  resolved "https://registry.yarnpkg.com/html-insert-assets/-/html-insert-assets-0.14.2.tgz#134ccfbfcc847ddc37b4e4a610c29ccfd846eea8"
-  integrity sha512-6jx1Btu9D1iGlSTLMEHsqSqt0c1WJVhGNz4bEjDQ9y17JpB+GVUzr8M0MXjwPpQHDtiWdTdQ3qvPMlLzNmDXaw==
-  dependencies:
-    mkdirp "^1.0.3"
-    parse5 "^6.0.0"
-
 http-cache-semantics@^4.1.0:
   version "4.1.0"
   resolved "https://registry.yarnpkg.com/http-cache-semantics/-/http-cache-semantics-4.1.0.tgz#49e91c5cbf36c9b94bcfcd71c23d5249ec74e390"
   integrity sha512-carPklcUh7ROWRK7Cv27RPtdhYhUsela/ue5/jKzjegVvXDqM2ILE9Q2BGn9JZJh1g87cp56su/FgQSzcWS8cQ==
 
+http-errors@1.8.1:
+  version "1.8.1"
+  resolved "https://registry.yarnpkg.com/http-errors/-/http-errors-1.8.1.tgz#7c3f28577cbc8a207388455dbd62295ed07bd68c"
+  integrity sha512-Kpk9Sm7NmI+RHhnj6OIWDI1d6fIoFAtFt9RLaTMRlg/8w49juAStsrBgp0Dp4OdxdVbRIeKhtCUvoi/RuAhO4g==
+  dependencies:
+    depd "~1.1.2"
+    inherits "2.0.4"
+    setprototypeof "1.2.0"
+    statuses ">= 1.5.0 < 2"
+    toidentifier "1.0.1"
+
 http-proxy-agent@^4.0.1:
   version "4.0.1"
   resolved "https://registry.yarnpkg.com/http-proxy-agent/-/http-proxy-agent-4.0.1.tgz#8a8c8ef7f5932ccf953c296ca8291b95aa74aa3a"
@@ -1982,6 +1433,15 @@
     agent-base "6"
     debug "4"
 
+http-proxy@^1.18.1:
+  version "1.18.1"
+  resolved "https://registry.yarnpkg.com/http-proxy/-/http-proxy-1.18.1.tgz#401541f0534884bbf95260334e72f88ee3976549"
+  integrity sha512-7mz/721AbnJwIVbnaSv1Cz3Am0ZLT/UBwkC92VlxhXv/k/BBQfM2fXElQNC27BVGr0uwUpplYPQM9LnaBMR5NQ==
+  dependencies:
+    eventemitter3 "^4.0.0"
+    follow-redirects "^1.0.0"
+    requires-port "^1.0.0"
+
 https-proxy-agent@^5.0.0:
   version "5.0.0"
   resolved "https://registry.yarnpkg.com/https-proxy-agent/-/https-proxy-agent-5.0.0.tgz#e2a90542abb68a762e0a0850f6c9edadfd8506b2"
@@ -1997,7 +1457,7 @@
   dependencies:
     ms "^2.0.0"
 
-iconv-lite@^0.4.24:
+iconv-lite@0.4.24, iconv-lite@^0.4.24:
   version "0.4.24"
   resolved "https://registry.yarnpkg.com/iconv-lite/-/iconv-lite-0.4.24.tgz#2022b4b25fbddc21d2f524974a474aafe733908b"
   integrity sha512-v3MXnZAcvnywkTUEZomIActle7RXXeedOR31wwl7VlyoXO4Qi9arvSenNQWne1TcRwhCL1HwLI21bEqdpj8/rA==
@@ -2046,7 +1506,7 @@
     once "^1.3.0"
     wrappy "1"
 
-inherits@2, inherits@^2.0.3, inherits@^2.0.4:
+inherits@2, inherits@2.0.4, inherits@^2.0.3, inherits@^2.0.4:
   version "2.0.4"
   resolved "https://registry.yarnpkg.com/inherits/-/inherits-2.0.4.tgz#0fa2c64f932917c3433a0ded55363aae37416b7c"
   integrity sha512-k/vGaX4/Yla3WzyMCvTQOXYeIHvqOKtnqBduzTHpzpQZzAskKMhZ2K+EnBiSM9zGSoIFeMpXKxa4dYeZIQqewQ==
@@ -2149,11 +1609,34 @@
   dependencies:
     is-docker "^2.0.0"
 
+isbinaryfile@^4.0.8:
+  version "4.0.8"
+  resolved "https://registry.yarnpkg.com/isbinaryfile/-/isbinaryfile-4.0.8.tgz#5d34b94865bd4946633ecc78a026fc76c5b11fcf"
+  integrity sha512-53h6XFniq77YdW+spoRrebh0mnmTxRPTlcuIArO57lmMdq4uBKFKaeTjnb92oYWrSn/LVL+LT+Hap2tFQj8V+w==
+
 isexe@^2.0.0:
   version "2.0.0"
   resolved "https://registry.yarnpkg.com/isexe/-/isexe-2.0.0.tgz#e8fbf374dc556ff8947a10dcb0572d633f2cfa10"
   integrity sha1-6PvzdNxVb/iUehDcsFctYz8s+hA=
 
+jasmine-core@^3.6.0:
+  version "3.99.0"
+  resolved "https://registry.yarnpkg.com/jasmine-core/-/jasmine-core-3.99.0.tgz#99a3da0d38ba2de82614d9198b7b1bc1c32a5960"
+  integrity sha512-+ZDaJlEfRopINQqgE+hvzRyDIQDeKfqqTvF8RzXsvU1yE3pBDRud2+Qfh9WvGgRpuzqxyQJVI6Amy5XQ11r/3w==
+
+jasmine-core@^4.0.0:
+  version "4.0.0"
+  resolved "https://registry.yarnpkg.com/jasmine-core/-/jasmine-core-4.0.0.tgz#8299ed38a100c47a1d154af63449a40967a7be5c"
+  integrity sha512-tq24OCqHElgU9KDpb/8O21r1IfotgjIzalfW9eCmRR40LZpvwXT68iariIyayMwi0m98RDt16aljdbwK0sBMmQ==
+
+jasmine@latest:
+  version "4.0.2"
+  resolved "https://registry.yarnpkg.com/jasmine/-/jasmine-4.0.2.tgz#6f5ff7fbf6b67f56600235fdb7d299ac52876c4b"
+  integrity sha512-YsrgxJQEggxzByYe4j68eQLOiQeSrPDYGv4sHhGBp3c6HHdq+uPXeAQ73kOAQpdLZ3/0zN7x/TZTloqeE1/qIA==
+  dependencies:
+    glob "^7.1.6"
+    jasmine-core "^4.0.0"
+
 js-tokens@^4.0.0:
   version "4.0.0"
   resolved "https://registry.yarnpkg.com/js-tokens/-/js-tokens-4.0.0.tgz#19203fb59991df98e3a287050d4647cdeaf32499"
@@ -2164,11 +1647,6 @@
   resolved "https://registry.yarnpkg.com/jsesc/-/jsesc-2.5.2.tgz#80564d2e483dacf6e8ef209650a67df3f0c283a4"
   integrity sha512-OYu7XEzjkCQ3C5Ps3QIZsQfNpqoJyZZA99wd9aWd05NCtC5pWOkShK2mkL6HXQR6/Cy2lbNdPlZBpuQHXE63gA==
 
-jsesc@~0.5.0:
-  version "0.5.0"
-  resolved "https://registry.yarnpkg.com/jsesc/-/jsesc-0.5.0.tgz#e7dee66e35d6fc16f710fe91d5cf69f70f08911d"
-  integrity sha1-597mbjXW/Bb3EP6R1c9p9w8IkR0=
-
 json-parse-even-better-errors@^2.3.0:
   version "2.3.1"
   resolved "https://registry.yarnpkg.com/json-parse-even-better-errors/-/json-parse-even-better-errors-2.3.1.tgz#7c47805a94319928e05777405dc12e1f7a4ee02d"
@@ -2191,15 +1669,82 @@
   resolved "https://registry.yarnpkg.com/jsonc-parser/-/jsonc-parser-3.0.0.tgz#abdd785701c7e7eaca8a9ec8cf070ca51a745a22"
   integrity sha512-fQzRfAbIBnR0IQvftw9FJveWiHp72Fg20giDrHz6TdfB12UH/uue0D3hm57UB5KgAVuniLMCaS8P1IMj9NR7cA==
 
+jsonfile@^6.0.1:
+  version "6.1.0"
+  resolved "https://registry.yarnpkg.com/jsonfile/-/jsonfile-6.1.0.tgz#bc55b2634793c679ec6403094eb13698a6ec0aae"
+  integrity sha512-5dgndWOriYSm5cnYaJNhalLNDKOqFwyDB/rr1E9ZsGciGvKPs8R2xYGCacuf3z6K1YKDz182fd+fY3cn3pMqXQ==
+  dependencies:
+    universalify "^2.0.0"
+  optionalDependencies:
+    graceful-fs "^4.1.6"
+
 jsonparse@^1.3.1:
   version "1.3.1"
   resolved "https://registry.yarnpkg.com/jsonparse/-/jsonparse-1.3.1.tgz#3f4dae4a91fac315f71062f8521cc239f1366280"
   integrity sha1-P02uSpH6wxX3EGL4UhzCOfE2YoA=
 
-lodash.debounce@^4.0.8:
-  version "4.0.8"
-  resolved "https://registry.yarnpkg.com/lodash.debounce/-/lodash.debounce-4.0.8.tgz#82d79bff30a67c4005ffd5e2515300ad9ca4d7af"
-  integrity sha1-gteb/zCmfEAF/9XiUVMArZyk168=
+karma-chrome-launcher@latest:
+  version "3.1.0"
+  resolved "https://registry.yarnpkg.com/karma-chrome-launcher/-/karma-chrome-launcher-3.1.0.tgz#805a586799a4d05f4e54f72a204979f3f3066738"
+  integrity sha512-3dPs/n7vgz1rxxtynpzZTvb9y/GIaW8xjAwcIGttLbycqoFtI7yo1NGnQi6oFTherRE+GIhCAHZC4vEqWGhNvg==
+  dependencies:
+    which "^1.2.1"
+
+karma-firefox-launcher@latest:
+  version "2.1.2"
+  resolved "https://registry.yarnpkg.com/karma-firefox-launcher/-/karma-firefox-launcher-2.1.2.tgz#9a38cc783c579a50f3ed2a82b7386186385cfc2d"
+  integrity sha512-VV9xDQU1QIboTrjtGVD4NCfzIH7n01ZXqy/qpBhnOeGVOkG5JYPEm8kuSd7psHE6WouZaQ9Ool92g8LFweSNMA==
+  dependencies:
+    is-wsl "^2.2.0"
+    which "^2.0.1"
+
+karma-jasmine@latest:
+  version "4.0.1"
+  resolved "https://registry.yarnpkg.com/karma-jasmine/-/karma-jasmine-4.0.1.tgz#b99e073b6d99a5196fc4bffc121b89313b0abd82"
+  integrity sha512-h8XDAhTiZjJKzfkoO1laMH+zfNlra+dEQHUAjpn5JV1zCPtOIVWGQjLBrqhnzQa/hrU2XrZwSyBa6XjEBzfXzw==
+  dependencies:
+    jasmine-core "^3.6.0"
+
+karma-requirejs@latest:
+  version "1.1.0"
+  resolved "https://registry.yarnpkg.com/karma-requirejs/-/karma-requirejs-1.1.0.tgz#fddae2cb87d7ebc16fb0222893564d7fee578798"
+  integrity sha1-/driy4fX68FvsCIok1ZNf+5Xh5g=
+
+karma-sourcemap-loader@latest:
+  version "0.3.8"
+  resolved "https://registry.yarnpkg.com/karma-sourcemap-loader/-/karma-sourcemap-loader-0.3.8.tgz#d4bae72fb7a8397328a62b75013d2df937bdcf9c"
+  integrity sha512-zorxyAakYZuBcHRJE+vbrK2o2JXLFWK8VVjiT/6P+ltLBUGUvqTEkUiQ119MGdOrK7mrmxXHZF1/pfT6GgIZ6g==
+  dependencies:
+    graceful-fs "^4.1.2"
+
+karma@latest:
+  version "6.3.11"
+  resolved "https://registry.yarnpkg.com/karma/-/karma-6.3.11.tgz#2c2fb09f1a9f52e1a0739adeedace2a68d4c0d34"
+  integrity sha512-QGUh4yXgizzDNPLB5nWTvP+wysKexngbyLVWFOyikB661hpa2RZLf5anZQzqliWtAQuYVep0ot0D1U7UQKpsxQ==
+  dependencies:
+    body-parser "^1.19.0"
+    braces "^3.0.2"
+    chokidar "^3.5.1"
+    colors "1.4.0"
+    connect "^3.7.0"
+    di "^0.0.1"
+    dom-serialize "^2.2.1"
+    glob "^7.1.7"
+    graceful-fs "^4.2.6"
+    http-proxy "^1.18.1"
+    isbinaryfile "^4.0.8"
+    lodash "^4.17.21"
+    log4js "^6.3.0"
+    mime "^2.5.2"
+    minimatch "^3.0.4"
+    qjobs "^1.2.0"
+    range-parser "^1.2.1"
+    rimraf "^3.0.2"
+    socket.io "^4.2.0"
+    source-map "^0.6.1"
+    tmp "^0.2.1"
+    ua-parser-js "^0.7.30"
+    yargs "^16.1.1"
 
 lodash@^4.17.21:
   version "4.17.21"
@@ -2214,6 +1759,17 @@
     chalk "^4.1.0"
     is-unicode-supported "^0.1.0"
 
+log4js@^6.3.0:
+  version "6.4.1"
+  resolved "https://registry.yarnpkg.com/log4js/-/log4js-6.4.1.tgz#9d3a8bf2c31c1e213fe3fc398a6053f7a2bc53e8"
+  integrity sha512-iUiYnXqAmNKiIZ1XSAitQ4TmNs8CdZYTAWINARF3LjnsLN8tY5m0vRwd6uuWj/yNY0YHxeZodnbmxKFUOM2rMg==
+  dependencies:
+    date-format "^4.0.3"
+    debug "^4.3.3"
+    flatted "^3.2.4"
+    rfdc "^1.3.0"
+    streamroller "^3.0.2"
+
 long@^4.0.0:
   version "4.0.0"
   resolved "https://registry.yarnpkg.com/long/-/long-4.0.0.tgz#9a7b71cfb7d361a194ea555241c92f7468d5bf28"
@@ -2263,6 +1819,28 @@
     socks-proxy-agent "^6.0.0"
     ssri "^8.0.0"
 
+media-typer@0.3.0:
+  version "0.3.0"
+  resolved "https://registry.yarnpkg.com/media-typer/-/media-typer-0.3.0.tgz#8710d7af0aa626f8fffa1ce00168545263255748"
+  integrity sha1-hxDXrwqmJvj/+hzgAWhUUmMlV0g=
+
+mime-db@1.51.0:
+  version "1.51.0"
+  resolved "https://registry.yarnpkg.com/mime-db/-/mime-db-1.51.0.tgz#d9ff62451859b18342d960850dc3cfb77e63fb0c"
+  integrity sha512-5y8A56jg7XVQx2mbv1lu49NR4dokRnhZYTtL+KGfaa27uq4pSTXkwQkFJl4pkRMyNFz/EtYDSkiiEHx3F7UN6g==
+
+mime-types@~2.1.24:
+  version "2.1.34"
+  resolved "https://registry.yarnpkg.com/mime-types/-/mime-types-2.1.34.tgz#5a712f9ec1503511a945803640fafe09d3793c24"
+  integrity sha512-6cP692WwGIs9XXdOO4++N+7qjqv0rqxxVvJ3VHPh/Sc9mVZcQP+ZGhkKiTvWMQRr2tbHkJP/Yn7Y0npb3ZBs4A==
+  dependencies:
+    mime-db "1.51.0"
+
+mime@^2.5.2:
+  version "2.6.0"
+  resolved "https://registry.yarnpkg.com/mime/-/mime-2.6.0.tgz#a2a682a95cd4d0cb1d6257e28f83da7e35800367"
+  integrity sha512-USPkMeET31rOMiarsBNIHZKLGgvKc/LrjofAnBlOttf5ajRvqiRA8QsenbcooctK6d6Ts6aqZXBA+XbkKthiQg==
+
 mimic-fn@^2.1.0:
   version "2.1.0"
   resolved "https://registry.yarnpkg.com/mimic-fn/-/mimic-fn-2.1.0.tgz#7ed2c2ccccaf84d3ffcb7a69b57711fc2083401b"
@@ -2347,6 +1925,11 @@
   resolved "https://registry.yarnpkg.com/mkdirp/-/mkdirp-1.0.4.tgz#3eb5ed62622756d79a5f0e2a221dfebad75c2f7e"
   integrity sha512-vVqVZQyf3WLx2Shd0qJ9xuvqgAyKPLAiqITEtqW0oIUjzo3PePDd6fW9iFz30ef7Ysp/oiWqbhszeGWW2T6Gzw==
 
+ms@2.0.0:
+  version "2.0.0"
+  resolved "https://registry.yarnpkg.com/ms/-/ms-2.0.0.tgz#5608aeadfc00be6c2901df5f9861788de0d597c8"
+  integrity sha1-VgiurfwAvmwpAd9fmGF4jeDVl8g=
+
 ms@2.1.2:
   version "2.1.2"
   resolved "https://registry.yarnpkg.com/ms/-/ms-2.1.2.tgz#d09d1f357b443f493382a8eb3ccd183872ae6009"
@@ -2362,7 +1945,7 @@
   resolved "https://registry.yarnpkg.com/mute-stream/-/mute-stream-0.0.8.tgz#1630c42b2251ff81e2a283de96a5497ea92e5e0d"
   integrity sha512-nnbWWOkoWyUsTjKrhgD0dcz22mdkSnpYqbEjIm2nhwhuxlSkpywJmBo8h0ZqJdkp73mb90SssHkN4rsRaBAfAA==
 
-negotiator@^0.6.2:
+negotiator@0.6.2, negotiator@^0.6.2:
   version "0.6.2"
   resolved "https://registry.yarnpkg.com/negotiator/-/negotiator-0.6.2.tgz#feacf7ccf525a77ae9634436a64883ffeca346fb"
   integrity sha512-hZXc7K2e+PgeI1eDBe/10Ard4ekbfrrqG8Ep+8Jmf4JID2bNg7NvCPOZN+kfF574pFQI7mum2AUqDidoKqcTOw==
@@ -2470,20 +2053,17 @@
     gauge "^4.0.0"
     set-blocking "^2.0.0"
 
-object-keys@^1.0.12, object-keys@^1.1.1:
-  version "1.1.1"
-  resolved "https://registry.yarnpkg.com/object-keys/-/object-keys-1.1.1.tgz#1c47f272df277f3b1daf061677d9c82e2322c60e"
-  integrity sha512-NuAESUOUMrlIXOfHKzD6bpPu3tYt3xvjNdRIQ+FeT0lNb4K8WR70CaDxhuNguS2XG+GjkyMwOzsN5ZktImfhLA==
+object-assign@^4:
+  version "4.1.1"
+  resolved "https://registry.yarnpkg.com/object-assign/-/object-assign-4.1.1.tgz#2109adc7965887cfc05cbbd442cac8bfbb360863"
+  integrity sha1-IQmtx5ZYh8/AXLvUQsrIv7s2CGM=
 
-object.assign@^4.1.0:
-  version "4.1.2"
-  resolved "https://registry.yarnpkg.com/object.assign/-/object.assign-4.1.2.tgz#0ed54a342eceb37b38ff76eb831a0e788cb63940"
-  integrity sha512-ixT2L5THXsApyiUPYKmW+2EHpXXe5Ii3M+f4e+aJFAHao5amFRW6J0OO6c/LU8Be47utCx2GL89hxGB6XSmKuQ==
+on-finished@~2.3.0:
+  version "2.3.0"
+  resolved "https://registry.yarnpkg.com/on-finished/-/on-finished-2.3.0.tgz#20f1336481b083cd75337992a16971aa2d906947"
+  integrity sha1-IPEzZIGwg811M3mSoWlxqi2QaUc=
   dependencies:
-    call-bind "^1.0.0"
-    define-properties "^1.1.3"
-    has-symbols "^1.0.1"
-    object-keys "^1.1.1"
+    ee-first "1.1.1"
 
 once@^1.3.0:
   version "1.4.0"
@@ -2560,10 +2140,10 @@
     ssri "^8.0.1"
     tar "^6.1.0"
 
-parse5@^6.0.0:
-  version "6.0.1"
-  resolved "https://registry.yarnpkg.com/parse5/-/parse5-6.0.1.tgz#e1a1c085c569b3dc08321184f19a39cc27f7c30b"
-  integrity sha512-Ofn/CTFzRGTTxwpNEs9PP93gXShHcTq255nzRYSKe8AkVpZY7e1fpmTfOyoIvjP5HG7Z2ZM7VS9PPhQGW2pOpw==
+parseurl@~1.3.3:
+  version "1.3.3"
+  resolved "https://registry.yarnpkg.com/parseurl/-/parseurl-1.3.3.tgz#9da19e7bee8d12dff0513ed5b76957793bc2e8d4"
+  integrity sha512-CiyeOxFT/JZyN5m0z9PfXw4SCBJ6Sygz1Dpl0wqjlhDEGGBP1GnsUVEL0p63hoG1fcj3fHynXi9NYO4nWOL+qQ==
 
 path-is-absolute@^1.0.0:
   version "1.0.1"
@@ -2627,6 +2207,31 @@
   resolved "https://registry.yarnpkg.com/punycode/-/punycode-2.1.1.tgz#b58b010ac40c22c5657616c8d2c2c02c7bf479ec"
   integrity sha512-XRsRjdf+j5ml+y/6GKHPZbrF/8p2Yga0JPtdqTIY2Xe5ohJPD9saDJJLPvp9+NSBprVvevdXZybnj2cv8OEd0A==
 
+qjobs@^1.2.0:
+  version "1.2.0"
+  resolved "https://registry.yarnpkg.com/qjobs/-/qjobs-1.2.0.tgz#c45e9c61800bd087ef88d7e256423bdd49e5d071"
+  integrity sha512-8YOJEHtxpySA3fFDyCRxA+UUV+fA+rTWnuWvylOK/NCjhY+b4ocCtmu8TtsWb+mYeU+GCHf/S66KZF/AsteKHg==
+
+qs@6.9.6:
+  version "6.9.6"
+  resolved "https://registry.yarnpkg.com/qs/-/qs-6.9.6.tgz#26ed3c8243a431b2924aca84cc90471f35d5a0ee"
+  integrity sha512-TIRk4aqYLNoJUbd+g2lEdz5kLWIuTMRagAXxl78Q0RiVjAOugHmeKNGdd3cwo/ktpf9aL9epCfFqWDEKysUlLQ==
+
+range-parser@^1.2.1:
+  version "1.2.1"
+  resolved "https://registry.yarnpkg.com/range-parser/-/range-parser-1.2.1.tgz#3cf37023d199e1c24d1a55b84800c2f3e6468031"
+  integrity sha512-Hrgsx+orqoygnmhFbKaHE6c296J+HTAQXoxEF6gNupROmmGJRoyzfG3ccAveqCBrwr/2yxQ5BVd/GTl5agOwSg==
+
+raw-body@2.4.2:
+  version "2.4.2"
+  resolved "https://registry.yarnpkg.com/raw-body/-/raw-body-2.4.2.tgz#baf3e9c21eebced59dd6533ac872b71f7b61cb32"
+  integrity sha512-RPMAFUJP19WIet/99ngh6Iv8fzAbqum4Li7AD6DtGaW2RpMB/11xDoalPiJMTbu6I3hkbMVkATvZrqb9EEqeeQ==
+  dependencies:
+    bytes "3.1.1"
+    http-errors "1.8.1"
+    iconv-lite "0.4.24"
+    unpipe "1.0.0"
+
 read-package-json-fast@^2.0.1:
   version "2.0.3"
   resolved "https://registry.yarnpkg.com/read-package-json-fast/-/read-package-json-fast-2.0.3.tgz#323ca529630da82cb34b36cc0b996693c98c2b83"
@@ -2656,54 +2261,6 @@
   resolved "https://registry.yarnpkg.com/reflect-metadata/-/reflect-metadata-0.1.13.tgz#67ae3ca57c972a2aa1642b10fe363fe32d49dc08"
   integrity sha512-Ts1Y/anZELhSsjMcU605fU9RE4Oi3p5ORujwbIKXfWa+0Zxs510Qrmrce5/Jowq3cHSZSJqBjypxmHarc+vEWg==
 
-regenerate-unicode-properties@^9.0.0:
-  version "9.0.0"
-  resolved "https://registry.yarnpkg.com/regenerate-unicode-properties/-/regenerate-unicode-properties-9.0.0.tgz#54d09c7115e1f53dc2314a974b32c1c344efe326"
-  integrity sha512-3E12UeNSPfjrgwjkR81m5J7Aw/T55Tu7nUyZVQYCKEOs+2dkxEY+DpPtZzO4YruuiPb7NkYLVcyJC4+zCbk5pA==
-  dependencies:
-    regenerate "^1.4.2"
-
-regenerate@^1.4.2:
-  version "1.4.2"
-  resolved "https://registry.yarnpkg.com/regenerate/-/regenerate-1.4.2.tgz#b9346d8827e8f5a32f7ba29637d398b69014848a"
-  integrity sha512-zrceR/XhGYU/d/opr2EKO7aRHUeiBI8qjtfHqADTwZd6Szfy16la6kqD0MIUs5z5hx6AaKa+PixpPrR289+I0A==
-
-regenerator-runtime@^0.13.4:
-  version "0.13.9"
-  resolved "https://registry.yarnpkg.com/regenerator-runtime/-/regenerator-runtime-0.13.9.tgz#8925742a98ffd90814988d7566ad30ca3b263b52"
-  integrity sha512-p3VT+cOEgxFsRRA9X4lkI1E+k2/CtnKtU4gcxyaCUreilL/vqI6CdZ3wxVUx3UOUg+gnUOQQcRI7BmSI656MYA==
-
-regenerator-transform@^0.14.2:
-  version "0.14.5"
-  resolved "https://registry.yarnpkg.com/regenerator-transform/-/regenerator-transform-0.14.5.tgz#c98da154683671c9c4dcb16ece736517e1b7feb4"
-  integrity sha512-eOf6vka5IO151Jfsw2NO9WpGX58W6wWmefK3I1zEGr0lOD0u8rwPaNqQL1aRxUaxLeKO3ArNh3VYg1KbaD+FFw==
-  dependencies:
-    "@babel/runtime" "^7.8.4"
-
-regexpu-core@^4.7.1:
-  version "4.8.0"
-  resolved "https://registry.yarnpkg.com/regexpu-core/-/regexpu-core-4.8.0.tgz#e5605ba361b67b1718478501327502f4479a98f0"
-  integrity sha512-1F6bYsoYiz6is+oz70NWur2Vlh9KWtswuRuzJOfeYUrfPX2o8n74AnUVaOGDbUqVGO9fNHu48/pjJO4sNVwsOg==
-  dependencies:
-    regenerate "^1.4.2"
-    regenerate-unicode-properties "^9.0.0"
-    regjsgen "^0.5.2"
-    regjsparser "^0.7.0"
-    unicode-match-property-ecmascript "^2.0.0"
-    unicode-match-property-value-ecmascript "^2.0.0"
-
-regjsgen@^0.5.2:
-  version "0.5.2"
-  resolved "https://registry.yarnpkg.com/regjsgen/-/regjsgen-0.5.2.tgz#92ff295fb1deecbf6ecdab2543d207e91aa33733"
-  integrity sha512-OFFT3MfrH90xIW8OOSyUrk6QHD5E9JOTeGodiJeBS3J6IwlgzJMNE/1bZklWz5oTg+9dCMyEetclvCVXOPoN3A==
-
-regjsparser@^0.7.0:
-  version "0.7.0"
-  resolved "https://registry.yarnpkg.com/regjsparser/-/regjsparser-0.7.0.tgz#a6b667b54c885e18b52554cb4960ef71187e9968"
-  integrity sha512-A4pcaORqmNMDVwUjWoTzuhwMGpP+NykpfqAsEgI1FSH/EzC7lrN5TMd+kN8YCovX+jMpu8eaqXgXPCa0g8FQNQ==
-  dependencies:
-    jsesc "~0.5.0"
-
 require-directory@^2.1.1:
   version "2.1.1"
   resolved "https://registry.yarnpkg.com/require-directory/-/require-directory-2.1.1.tgz#8c64ad5fd30dab1c976e2344ffe7f792a6a6df42"
@@ -2714,6 +2271,16 @@
   resolved "https://registry.yarnpkg.com/require-from-string/-/require-from-string-2.0.2.tgz#89a7fdd938261267318eafe14f9c32e598c36909"
   integrity sha512-Xf0nWe6RseziFMu+Ap9biiUbmplq6S9/p+7w7YXP/JBHhrUDDUhwa+vANyubuqfZWTveU//DYVGsDG7RKL/vEw==
 
+requirejs@latest:
+  version "2.3.6"
+  resolved "https://registry.yarnpkg.com/requirejs/-/requirejs-2.3.6.tgz#e5093d9601c2829251258c0b9445d4d19fa9e7c9"
+  integrity sha512-ipEzlWQe6RK3jkzikgCupiTbTvm4S0/CAU5GlgptkN5SO6F3u0UD0K18wy6ErDqiCyP4J4YYe1HuAShvsxePLg==
+
+requires-port@^1.0.0:
+  version "1.0.0"
+  resolved "https://registry.yarnpkg.com/requires-port/-/requires-port-1.0.0.tgz#925d2601d39ac485e091cf0da5c6e694dc3dcaff"
+  integrity sha1-kl0mAdOaxIXgkc8NpcbmlNw9yv8=
+
 resolve@1.20.0:
   version "1.20.0"
   resolved "https://registry.yarnpkg.com/resolve/-/resolve-1.20.0.tgz#629a013fb3f70755d6f0b7935cc1c2c5378b1975"
@@ -2722,7 +2289,7 @@
     is-core-module "^2.2.0"
     path-parse "^1.0.6"
 
-resolve@^1.14.2, resolve@^1.19.0:
+resolve@^1.19.0:
   version "1.21.0"
   resolved "https://registry.yarnpkg.com/resolve/-/resolve-1.21.0.tgz#b51adc97f3472e6a5cf4444d34bc9d6b9037591f"
   integrity sha512-3wCbTpk5WJlyE4mSOtDLhqQmGFi0/TD9VPwmiolnk8U0wRgMEktqCXd3vy5buTO3tljvalNvKrjHEfrd2WpEKA==
@@ -2744,7 +2311,12 @@
   resolved "https://registry.yarnpkg.com/retry/-/retry-0.12.0.tgz#1b42a6266a21f07421d1b0b54b7dc167b01c013b"
   integrity sha1-G0KmJmoh8HQh0bC1S33BZ7AcATs=
 
-rimraf@^3.0.2:
+rfdc@^1.3.0:
+  version "1.3.0"
+  resolved "https://registry.yarnpkg.com/rfdc/-/rfdc-1.3.0.tgz#d0b7c441ab2720d05dc4cf26e01c89631d9da08b"
+  integrity sha512-V2hovdzFbOi77/WajaSMXk2OLm+xNIeQdMMuB7icj7bk6zi2F8GGAxigcnDFpJHbNyNcgyJDiP+8nOrY5cZGrA==
+
+rimraf@^3.0.0, rimraf@^3.0.2:
   version "3.0.2"
   resolved "https://registry.yarnpkg.com/rimraf/-/rimraf-3.0.2.tgz#f1a5402ba6220ad52cc1282bac1ae3aa49fd061a"
   integrity sha512-JZkJMZkAGFFPP2YqXZXPbMlMBgsxzE8ILs4lMIX/2o0L9UBw9O/Y3o6wFw/i9YLapcUJWwqbi3kdxIPdC62TIA==
@@ -2797,11 +2369,6 @@
   resolved "https://registry.yarnpkg.com/semver/-/semver-5.6.0.tgz#7e74256fbaa49c75aa7c7a205cc22799cac80004"
   integrity sha512-RS9R6R35NYgQn++fkDWaOmqGoj4Ek9gGs+DPxNUZKuwE183xjJroKvyo1IzVFeXvUrvmALy6FWD5xrdJT25gMg==
 
-semver@7.0.0:
-  version "7.0.0"
-  resolved "https://registry.yarnpkg.com/semver/-/semver-7.0.0.tgz#5f3ca35761e47e05b206c6daff2cf814f0316b8e"
-  integrity sha512-+GB6zVA9LWh6zovYQLALHwv5rb2PHGlJi3lfiqIHxR0uuwCgefcOJc59v9fv1w8GbStwxuuqqAjI9NMAOOgq1A==
-
 semver@7.3.5, semver@^7.0.0, semver@^7.1.1, semver@^7.3.4, semver@^7.3.5:
   version "7.3.5"
   resolved "https://registry.yarnpkg.com/semver/-/semver-7.3.5.tgz#0b621c879348d8998e4b0e4be94b3f12e6018ef7"
@@ -2814,7 +2381,7 @@
   resolved "https://registry.yarnpkg.com/semver/-/semver-5.7.1.tgz#a954f931aeba508d307bbf069eff0c01c96116f7"
   integrity sha512-sauaDf/PZdVgrLTNYHRtpXa1iRiKcaebiKQ1BJdpQlWH2lCvexQdX55snPFyK7QzpudqbCI0qXFfOasHdyNDGQ==
 
-semver@^6.1.1, semver@^6.1.2, semver@^6.3.0:
+semver@^6.3.0:
   version "6.3.0"
   resolved "https://registry.yarnpkg.com/semver/-/semver-6.3.0.tgz#ee0a64c8af5e8ceea67687b133761e1becbd1d3d"
   integrity sha512-b39TBaTSfV6yBrapU89p5fKekE2m/NwnDocOVruQFS1/veMgdzuPcnOM34M6CwxW8jH/lxEa5rBoDeUwu5HHTw==
@@ -2824,6 +2391,11 @@
   resolved "https://registry.yarnpkg.com/set-blocking/-/set-blocking-2.0.0.tgz#045f9782d011ae9a6803ddd382b24392b3d890f7"
   integrity sha1-BF+XgtARrppoA93TgrJDkrPYkPc=
 
+setprototypeof@1.2.0:
+  version "1.2.0"
+  resolved "https://registry.yarnpkg.com/setprototypeof/-/setprototypeof-1.2.0.tgz#66c9a24a73f9fc28cbe66b09fed3d33dcaf1b424"
+  integrity sha512-E5LDX7Wrp85Kil5bhZv46j8jOeboKq5JMmYM3gVGdGH8xFpPWXUMsNrlODCrkoxMEeNi/XZIwuRvY4XNwYMJpw==
+
 signal-exit@^3.0.0, signal-exit@^3.0.2:
   version "3.0.6"
   resolved "https://registry.yarnpkg.com/signal-exit/-/signal-exit-3.0.6.tgz#24e630c4b0f03fea446a2bd299e62b4a6ca8d0af"
@@ -2839,6 +2411,32 @@
   resolved "https://registry.yarnpkg.com/smart-buffer/-/smart-buffer-4.2.0.tgz#6e1d71fa4f18c05f7d0ff216dd16a481d0e8d9ae"
   integrity sha512-94hK0Hh8rPqQl2xXc3HsaBoOXKV20MToPkcXvwbISWLEs+64sBq5kFgn2kJDHb1Pry9yrP0dxrCI9RRci7RXKg==
 
+socket.io-adapter@~2.3.3:
+  version "2.3.3"
+  resolved "https://registry.yarnpkg.com/socket.io-adapter/-/socket.io-adapter-2.3.3.tgz#4d6111e4d42e9f7646e365b4f578269821f13486"
+  integrity sha512-Qd/iwn3VskrpNO60BeRyCyr8ZWw9CPZyitW4AQwmRZ8zCiyDiL+znRnWX6tDHXnWn1sJrM1+b6Mn6wEDJJ4aYQ==
+
+socket.io-parser@~4.0.4:
+  version "4.0.4"
+  resolved "https://registry.yarnpkg.com/socket.io-parser/-/socket.io-parser-4.0.4.tgz#9ea21b0d61508d18196ef04a2c6b9ab630f4c2b0"
+  integrity sha512-t+b0SS+IxG7Rxzda2EVvyBZbvFPBCjJoyHuE0P//7OAsN23GItzDRdWa6ALxZI/8R5ygK7jAR6t028/z+7295g==
+  dependencies:
+    "@types/component-emitter" "^1.2.10"
+    component-emitter "~1.3.0"
+    debug "~4.3.1"
+
+socket.io@^4.2.0:
+  version "4.4.1"
+  resolved "https://registry.yarnpkg.com/socket.io/-/socket.io-4.4.1.tgz#cd6de29e277a161d176832bb24f64ee045c56ab8"
+  integrity sha512-s04vrBswdQBUmuWJuuNTmXUVJhP0cVky8bBDhdkf8y0Ptsu7fKU2LuLbts9g+pdmAdyMMn8F/9Mf1/wbtUN0fg==
+  dependencies:
+    accepts "~1.3.4"
+    base64id "~2.0.0"
+    debug "~4.3.2"
+    engine.io "~6.1.0"
+    socket.io-adapter "~2.3.3"
+    socket.io-parser "~4.0.4"
+
 socks-proxy-agent@^6.0.0:
   version "6.1.1"
   resolved "https://registry.yarnpkg.com/socks-proxy-agent/-/socks-proxy-agent-6.1.1.tgz#e664e8f1aaf4e1fb3df945f09e3d94f911137f87"
@@ -2881,9 +2479,10 @@
   resolved "https://registry.yarnpkg.com/source-map/-/source-map-0.5.7.tgz#8a039d2d1021d22d1ea14c80d8ea468ba2ef3fcc"
   integrity sha1-igOdLRAh0i0eoUyA2OpGi6LvP8w=
 
-source-map@^0.6.0:
+source-map@^0.6.0, source-map@^0.6.1:
   version "0.6.1"
   resolved "https://registry.yarnpkg.com/source-map/-/source-map-0.6.1.tgz#74722af32e9614e9c287a8d0bbde48b5e2f1a263"
+  integrity sha512-UjgapumWlbMhkBgzT7Ykc5YXUT46F0iKu8SGXq0bcwP5dz/h0Plj6enJqjz1Zbq2l5WaqYnrVbwWOWMyF3F47g==
 
 sourcemap-codec@^1.4.4, sourcemap-codec@^1.4.8:
   version "1.4.8"
@@ -2897,6 +2496,20 @@
   dependencies:
     minipass "^3.1.1"
 
+"statuses@>= 1.5.0 < 2", statuses@~1.5.0:
+  version "1.5.0"
+  resolved "https://registry.yarnpkg.com/statuses/-/statuses-1.5.0.tgz#161c7dac177659fd9811f43771fa99381478628c"
+  integrity sha1-Fhx9rBd2Wf2YEfQ3cfqZOBR4Yow=
+
+streamroller@^3.0.2:
+  version "3.0.2"
+  resolved "https://registry.yarnpkg.com/streamroller/-/streamroller-3.0.2.tgz#30418d0eee3d6c93ec897f892ed098e3a81e68b7"
+  integrity sha512-ur6y5S5dopOaRXBuRIZ1u6GC5bcEXHRZKgfBjfCglMhmIf+roVCECjvkEYzNQOXIN2/JPnkMPW/8B3CZoKaEPA==
+  dependencies:
+    date-format "^4.0.3"
+    debug "^4.1.1"
+    fs-extra "^10.0.0"
+
 "string-width@^1.0.2 || 2 || 3 || 4", string-width@^4.1.0, string-width@^4.2.0, string-width@^4.2.3:
   version "4.2.3"
   resolved "https://registry.yarnpkg.com/string-width/-/string-width-4.2.3.tgz#269c7117d27b05ad2e536830a8ec895ef9c6d010"
@@ -2977,6 +2590,13 @@
   dependencies:
     os-tmpdir "~1.0.2"
 
+tmp@^0.2.1:
+  version "0.2.1"
+  resolved "https://registry.yarnpkg.com/tmp/-/tmp-0.2.1.tgz#8457fc3037dcf4719c251367a1af6500ee1ccf14"
+  integrity sha512-76SUhtfqR2Ijn+xllcI5P1oyannHNHByD80W1q447gU3mp9G9PSpGdWmjUOHRDPiHYacIk66W7ubDTuPF3BEtQ==
+  dependencies:
+    rimraf "^3.0.0"
+
 to-fast-properties@^2.0.0:
   version "2.0.0"
   resolved "https://registry.yarnpkg.com/to-fast-properties/-/to-fast-properties-2.0.0.tgz#dc5e698cbd079265bc73e0377681a4e4e83f616e"
@@ -2989,6 +2609,11 @@
   dependencies:
     is-number "^7.0.0"
 
+toidentifier@1.0.1:
+  version "1.0.1"
+  resolved "https://registry.yarnpkg.com/toidentifier/-/toidentifier-1.0.1.tgz#3be34321a88a820ed1bd80dfaa33e479fbb8dd35"
+  integrity sha512-o5sSPKEkg/DIQNmH43V0/uerLrpzVedkUh8tGNvaeXpfpuwjKenlSox/2O/BTlZUtEe+JG7s5YhEz608PlAHRA==
+
 tslib@^1.8.1:
   version "1.9.3"
   resolved "https://registry.yarnpkg.com/tslib/-/tslib-1.9.3.tgz#d7e4dd79245d85428c4d7e4822a79917954ca286"
@@ -3015,33 +2640,23 @@
   resolved "https://registry.yarnpkg.com/type-fest/-/type-fest-0.21.3.tgz#d260a24b0198436e133fa26a524a6d65fa3b2e37"
   integrity sha512-t0rzBq87m3fVcduHDUFhKmyyX+9eo6WQjZvf51Ea/M0Q7+T374Jp1aUiyUl0GKxp8M/OETVHSDvmkyPgvX+X2w==
 
+type-is@~1.6.18:
+  version "1.6.18"
+  resolved "https://registry.yarnpkg.com/type-is/-/type-is-1.6.18.tgz#4e552cd05df09467dcbc4ef739de89f2cf37c131"
+  integrity sha512-TkRKr9sUTxEH8MdfuCSP7VizJyzRNMjj2J2do2Jr3Kym598JVdEksuzPQCnlFPW4ky9Q+iA+ma9BGm06XQBy8g==
+  dependencies:
+    media-typer "0.3.0"
+    mime-types "~2.1.24"
+
 typescript@latest:
   version "4.5.4"
   resolved "https://registry.yarnpkg.com/typescript/-/typescript-4.5.4.tgz#a17d3a0263bf5c8723b9c52f43c5084edf13c2e8"
   integrity sha512-VgYs2A2QIRuGphtzFV7aQJduJ2gyfTljngLzjpfW9FoYZF6xuw1W0vW9ghCKLfcWrCFxK81CSGRAvS1pn4fIUg==
 
-unicode-canonical-property-names-ecmascript@^2.0.0:
-  version "2.0.0"
-  resolved "https://registry.yarnpkg.com/unicode-canonical-property-names-ecmascript/-/unicode-canonical-property-names-ecmascript-2.0.0.tgz#301acdc525631670d39f6146e0e77ff6bbdebddc"
-  integrity sha512-yY5PpDlfVIU5+y/BSCxAJRBIS1Zc2dDG3Ujq+sR0U+JjUevW2JhocOF+soROYDSaAezOzOKuyyixhD6mBknSmQ==
-
-unicode-match-property-ecmascript@^2.0.0:
-  version "2.0.0"
-  resolved "https://registry.yarnpkg.com/unicode-match-property-ecmascript/-/unicode-match-property-ecmascript-2.0.0.tgz#54fd16e0ecb167cf04cf1f756bdcc92eba7976c3"
-  integrity sha512-5kaZCrbp5mmbz5ulBkDkbY0SsPOjKqVS35VpL9ulMPfSl0J0Xsm+9Evphv9CoIZFwre7aJoa94AY6seMKGVN5Q==
-  dependencies:
-    unicode-canonical-property-names-ecmascript "^2.0.0"
-    unicode-property-aliases-ecmascript "^2.0.0"
-
-unicode-match-property-value-ecmascript@^2.0.0:
-  version "2.0.0"
-  resolved "https://registry.yarnpkg.com/unicode-match-property-value-ecmascript/-/unicode-match-property-value-ecmascript-2.0.0.tgz#1a01aa57247c14c568b89775a54938788189a714"
-  integrity sha512-7Yhkc0Ye+t4PNYzOGKedDhXbYIBe1XEQYQxOPyhcXNMJ0WCABqqj6ckydd6pWRZTHV4GuCPKdBAUiMc60tsKVw==
-
-unicode-property-aliases-ecmascript@^2.0.0:
-  version "2.0.0"
-  resolved "https://registry.yarnpkg.com/unicode-property-aliases-ecmascript/-/unicode-property-aliases-ecmascript-2.0.0.tgz#0a36cb9a585c4f6abd51ad1deddb285c165297c8"
-  integrity sha512-5Zfuy9q/DFr4tfO7ZPeVXb1aPoeQSdeFMLpYuFebehDAhbuevLs5yxSZmIFN1tP5F9Wl4IpJrYojg85/zgyZHQ==
+ua-parser-js@^0.7.30:
+  version "0.7.31"
+  resolved "https://registry.yarnpkg.com/ua-parser-js/-/ua-parser-js-0.7.31.tgz#649a656b191dffab4f21d5e053e27ca17cbff5c6"
+  integrity sha512-qLK/Xe9E2uzmYI3qLeOmI0tEOt+TBBQyUIAh4aAgU05FVYzeZrKUdkAZfBNVGRaHVgV0TDkdEngJSw/SyQchkQ==
 
 unique-filename@^1.1.1:
   version "1.1.1"
@@ -3057,6 +2672,16 @@
   dependencies:
     imurmurhash "^0.1.4"
 
+universalify@^2.0.0:
+  version "2.0.0"
+  resolved "https://registry.yarnpkg.com/universalify/-/universalify-2.0.0.tgz#75a4984efedc4b08975c5aeb73f530d02df25717"
+  integrity sha512-hAZsKq7Yy11Zu1DE0OzWjw7nnLZmJZYTDZZyEFHZdUhV8FkH5MCfoU1XMaxXovpyW5nq5scPqq0ZDP9Zyl04oQ==
+
+unpipe@1.0.0, unpipe@~1.0.0:
+  version "1.0.0"
+  resolved "https://registry.yarnpkg.com/unpipe/-/unpipe-1.0.0.tgz#b2bf4ee8514aae6165b4817829d21b2ef49904ec"
+  integrity sha1-sr9O6FFKrmFltIF4KdIbLvSZBOw=
+
 uri-js@^4.2.2:
   version "4.4.1"
   resolved "https://registry.yarnpkg.com/uri-js/-/uri-js-4.4.1.tgz#9b1a52595225859e55f669d928f88c6c57f2a77e"
@@ -3069,6 +2694,11 @@
   resolved "https://registry.yarnpkg.com/util-deprecate/-/util-deprecate-1.0.2.tgz#450d4dc9fa70de732762fbd2d4a28981419a0ccf"
   integrity sha1-RQ1Nyfpw3nMnYvvS1KKJgUGaDM8=
 
+utils-merge@1.0.1:
+  version "1.0.1"
+  resolved "https://registry.yarnpkg.com/utils-merge/-/utils-merge-1.0.1.tgz#9f95710f50a267947b2ccc124741c1028427e713"
+  integrity sha1-n5VxD1CiZ5R7LMwSR0HBAoQn5xM=
+
 uuid@8.3.2:
   version "8.3.2"
   resolved "https://registry.yarnpkg.com/uuid/-/uuid-8.3.2.tgz#80d5b5ced271bb9af6c445f21a1a04c606cefbe2"
@@ -3081,6 +2711,16 @@
   dependencies:
     builtins "^1.0.3"
 
+vary@^1:
+  version "1.1.2"
+  resolved "https://registry.yarnpkg.com/vary/-/vary-1.1.2.tgz#2299f02c6ded30d4a5961b0b9f74524a18f634fc"
+  integrity sha1-IpnwLG3tMNSllhsLn3RSShj2NPw=
+
+void-elements@^2.0.0:
+  version "2.0.1"
+  resolved "https://registry.yarnpkg.com/void-elements/-/void-elements-2.0.1.tgz#c066afb582bb1cb4128d60ea92392e94d5e9dbec"
+  integrity sha1-wGavtYK7HLQSjWDqkjkulNXp2+w=
+
 wcwidth@^1.0.1:
   version "1.0.1"
   resolved "https://registry.yarnpkg.com/wcwidth/-/wcwidth-1.0.1.tgz#f0b0dcf915bc5ff1528afadb2c0e17b532da2fe8"
@@ -3088,7 +2728,14 @@
   dependencies:
     defaults "^1.0.3"
 
-which@^2.0.2:
+which@^1.2.1:
+  version "1.3.1"
+  resolved "https://registry.yarnpkg.com/which/-/which-1.3.1.tgz#a45043d54f5805316da8d62f9f50918d3da70b0a"
+  integrity sha512-HxJdYWq1MTIQbJ3nw0cqssHoTNU267KlrDuGZ1WYlxDStUtKUhOaJmh112/TZmHxxUfuJqPXSOm7tDyas0OSIQ==
+  dependencies:
+    isexe "^2.0.0"
+
+which@^2.0.1, which@^2.0.2:
   version "2.0.2"
   resolved "https://registry.yarnpkg.com/which/-/which-2.0.2.tgz#7c6a8dd0a636a0327e10b59c9286eee93f3f51b1"
   integrity sha512-BLI3Tl1TW3Pvl70l3yq3Y64i+awpwXqsGBYWkkqMtnbXgrMD+yj7rhW0kuEDxzJaYXGjEW5ogapKNMEKNMjibA==
@@ -3116,6 +2763,11 @@
   resolved "https://registry.yarnpkg.com/wrappy/-/wrappy-1.0.2.tgz#b5243d8f3ec1aa35f1364605bc0d1036e30ab69f"
   integrity sha1-tSQ9jz7BqjXxNkYFvA0QNuMKtp8=
 
+ws@~8.2.3:
+  version "8.2.3"
+  resolved "https://registry.yarnpkg.com/ws/-/ws-8.2.3.tgz#63a56456db1b04367d0b721a0b80cae6d8becbba"
+  integrity sha512-wBuoj1BDpC6ZQ1B7DWQBYVLphPWkm8i9Y0/3YdHjHKHiohOJ1ws+3OccDWtH+PoC9DZD5WOTrJvNbWvjS6JWaA==
+
 y18n@^5.0.5:
   version "5.0.8"
   resolved "https://registry.yarnpkg.com/y18n/-/y18n-5.0.8.tgz#7f4934d0f7ca8c56f95314939ddcd2dd91ce1d55"
@@ -3126,11 +2778,29 @@
   resolved "https://registry.yarnpkg.com/yallist/-/yallist-4.0.0.tgz#9bb92790d9c0effec63be73519e11a35019a3a72"
   integrity sha512-3wdGidZyq5PB084XLES5TpOSRA3wjXAlIWMhum2kRcv/41Sn2emQ0dycQW4uZXLejwKvg6EsvbdlVL+FYEct7A==
 
+yargs-parser@^20.2.2:
+  version "20.2.9"
+  resolved "https://registry.yarnpkg.com/yargs-parser/-/yargs-parser-20.2.9.tgz#2eb7dc3b0289718fc295f362753845c41a0c94ee"
+  integrity sha512-y11nGElTIV+CT3Zv9t7VKl+Q3hTQoT9a1Qzezhhl6Rp21gJ/IVTW7Z3y9EWXhuUBC2Shnf+DX0antecpAwSP8w==
+
 yargs-parser@^21.0.0:
   version "21.0.0"
   resolved "https://registry.yarnpkg.com/yargs-parser/-/yargs-parser-21.0.0.tgz#a485d3966be4317426dd56bdb6a30131b281dc55"
   integrity sha512-z9kApYUOCwoeZ78rfRYYWdiU/iNL6mwwYlkkZfJoyMR1xps+NEBX5X7XmRpxkZHhXJ6+Ey00IwKxBBSW9FIjyA==
 
+yargs@^16.1.1:
+  version "16.2.0"
+  resolved "https://registry.yarnpkg.com/yargs/-/yargs-16.2.0.tgz#1c82bf0f6b6a66eafce7ef30e376f49a12477f66"
+  integrity sha512-D1mvvtDG0L5ft/jGWkLpG1+m0eQxOfaBvTNELraWj22wSVUMWxZUvYgJYcKh6jGGIkJFhH4IZPQhR4TKpc8mBw==
+  dependencies:
+    cliui "^7.0.2"
+    escalade "^3.1.1"
+    get-caller-file "^2.0.5"
+    require-directory "^2.1.1"
+    string-width "^4.2.0"
+    y18n "^5.0.5"
+    yargs-parser "^20.2.2"
+
 yargs@^17.2.1:
   version "17.3.1"
   resolved "https://registry.yarnpkg.com/yargs/-/yargs-17.3.1.tgz#da56b28f32e2fd45aefb402ed9c26f42be4c07b9"